mirror of
https://github.com/esphome/esphome.git
synced 2025-09-07 13:52:20 +01:00
add missing immplementation
This commit is contained in:
@@ -34,6 +34,8 @@ from .const import (
|
|||||||
# force import gpio to register pin schema
|
# force import gpio to register pin schema
|
||||||
from .gpio import nrf52_pin_to_code # noqa
|
from .gpio import nrf52_pin_to_code # noqa
|
||||||
|
|
||||||
|
AUTO_LOAD = ["zephyr"]
|
||||||
|
|
||||||
|
|
||||||
def set_core_data(config):
|
def set_core_data(config):
|
||||||
zephyr_set_core_data(config)
|
zephyr_set_core_data(config)
|
||||||
|
@@ -1,49 +0,0 @@
|
|||||||
#ifdef USE_NRF52
|
|
||||||
#ifdef USE_ZEPHYR
|
|
||||||
|
|
||||||
#include <stdlib.h>
|
|
||||||
#include <zephyr/kernel.h>
|
|
||||||
|
|
||||||
namespace esphome {
|
|
||||||
void yield() { ::k_yield(); }
|
|
||||||
uint32_t millis() { return k_ticks_to_ms_floor32(k_uptime_ticks()); }
|
|
||||||
void delay(uint32_t ms) { ::k_msleep(ms); }
|
|
||||||
uint32_t micros() { return k_ticks_to_us_floor32(k_uptime_ticks()); }
|
|
||||||
|
|
||||||
void arch_init() {
|
|
||||||
// TODO
|
|
||||||
}
|
|
||||||
void arch_feed_wdt() {
|
|
||||||
// TODO
|
|
||||||
}
|
|
||||||
|
|
||||||
void arch_restart() {
|
|
||||||
// TODO
|
|
||||||
}
|
|
||||||
|
|
||||||
void nrf52GetMacAddr(uint8_t *mac) {
|
|
||||||
const uint8_t *src = (const uint8_t *) NRF_FICR->DEVICEADDR;
|
|
||||||
mac[5] = src[0];
|
|
||||||
mac[4] = src[1];
|
|
||||||
mac[3] = src[2];
|
|
||||||
mac[2] = src[3];
|
|
||||||
mac[1] = src[4];
|
|
||||||
mac[0] = src[5] | 0xc0; // MSB high two bits get set elsewhere in the bluetooth stack
|
|
||||||
}
|
|
||||||
|
|
||||||
} // namespace esphome
|
|
||||||
|
|
||||||
void setup();
|
|
||||||
void loop();
|
|
||||||
|
|
||||||
int main() {
|
|
||||||
setup();
|
|
||||||
while (1) {
|
|
||||||
loop();
|
|
||||||
esphome::yield();
|
|
||||||
}
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
|
||||||
#endif // USE_RP2040
|
|
@@ -1,13 +1,14 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#ifdef USE_NRF52
|
|
||||||
#include "esphome/core/hal.h"
|
#include "esphome/core/hal.h"
|
||||||
#ifdef USE_ZEPHYR
|
#ifdef USE_ZEPHYR
|
||||||
struct device;
|
#include "esphome/components/zephyr/gpio.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
namespace esphome {
|
namespace esphome {
|
||||||
namespace nrf52 {
|
namespace nrf52 {
|
||||||
|
|
||||||
|
#ifdef USE_ARDUINO
|
||||||
class NRF52GPIOPin : public InternalGPIOPin {
|
class NRF52GPIOPin : public InternalGPIOPin {
|
||||||
public:
|
public:
|
||||||
void set_pin(uint8_t pin) { pin_ = pin; }
|
void set_pin(uint8_t pin) { pin_ = pin; }
|
||||||
@@ -29,13 +30,9 @@ class NRF52GPIOPin : public InternalGPIOPin {
|
|||||||
uint8_t pin_;
|
uint8_t pin_;
|
||||||
bool inverted_;
|
bool inverted_;
|
||||||
gpio::Flags flags_;
|
gpio::Flags flags_;
|
||||||
#ifdef USE_ZEPHYR
|
|
||||||
const device *gpio_ = nullptr;
|
|
||||||
bool value_ = false;
|
|
||||||
#endif
|
|
||||||
};
|
};
|
||||||
|
#else
|
||||||
|
class NRF52GPIOPin : public zephyr::NRF52GPIOPin {};
|
||||||
|
#endif // USE_ARDUINO
|
||||||
} // namespace nrf52
|
} // namespace nrf52
|
||||||
} // namespace esphome
|
} // namespace esphome
|
||||||
|
|
||||||
#endif // USE_NRF52
|
|
||||||
|
@@ -82,12 +82,12 @@ def zephyr_to_code(conf):
|
|||||||
zephyr_add_prj_conf("DEBUG_THREAD_INFO", True)
|
zephyr_add_prj_conf("DEBUG_THREAD_INFO", True)
|
||||||
# zephyr_add_prj_conf("DEBUG", True)
|
# zephyr_add_prj_conf("DEBUG", True)
|
||||||
###
|
###
|
||||||
# zephyr_add_prj_conf("USE_SEGGER_RTT", True)
|
zephyr_add_prj_conf("USE_SEGGER_RTT", True)
|
||||||
# zephyr_add_prj_conf("RTT_CONSOLE", True)
|
zephyr_add_prj_conf("RTT_CONSOLE", True)
|
||||||
# zephyr_add_prj_conf("LOG", True)
|
zephyr_add_prj_conf("LOG", True)
|
||||||
|
|
||||||
# zephyr_add_prj_conf("USB_DEVICE_LOG_LEVEL_ERR", True)
|
# zephyr_add_prj_conf("USB_DEVICE_LOG_LEVEL_ERR", True)
|
||||||
# zephyr_add_prj_conf("USB_CDC_ACM_LOG_LEVEL_DBG", True)
|
zephyr_add_prj_conf("USB_CDC_ACM_LOG_LEVEL_WRN", True)
|
||||||
|
|
||||||
|
|
||||||
def _format_prj_conf_val(value: PrjConfValueType) -> str:
|
def _format_prj_conf_val(value: PrjConfValueType) -> str:
|
||||||
|
53
esphome/components/zephyr/core.cpp
Normal file
53
esphome/components/zephyr/core.cpp
Normal file
@@ -0,0 +1,53 @@
|
|||||||
|
#ifdef USE_ZEPHYR
|
||||||
|
|
||||||
|
#include <zephyr/kernel.h>
|
||||||
|
#include <zephyr/drivers/watchdog.h>
|
||||||
|
#include <zephyr/sys/reboot.h>
|
||||||
|
|
||||||
|
namespace esphome {
|
||||||
|
|
||||||
|
static int wdt_channel_id = -EINVAL;
|
||||||
|
const device * wdt = nullptr;
|
||||||
|
|
||||||
|
void yield() { ::k_yield(); }
|
||||||
|
uint32_t millis() { return k_ticks_to_ms_floor32(k_uptime_ticks()); }
|
||||||
|
void delay(uint32_t ms) { ::k_msleep(ms); }
|
||||||
|
uint32_t micros() { return k_ticks_to_us_floor32(k_uptime_ticks()); }
|
||||||
|
|
||||||
|
void arch_init() {
|
||||||
|
wdt = DEVICE_DT_GET(DT_ALIAS(watchdog0));
|
||||||
|
|
||||||
|
if (device_is_ready(wdt)) {
|
||||||
|
static wdt_timeout_cfg wdt_config{};
|
||||||
|
wdt_config.flags = WDT_FLAG_RESET_SOC;
|
||||||
|
wdt_config.window.max = 2000;
|
||||||
|
wdt_channel_id = wdt_install_timeout(wdt, &wdt_config);
|
||||||
|
if (wdt_channel_id >= 0) {
|
||||||
|
wdt_setup(wdt, WDT_OPT_PAUSE_HALTED_BY_DBG);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void arch_feed_wdt() {
|
||||||
|
if (wdt_channel_id >= 0) {
|
||||||
|
wdt_feed(wdt, wdt_channel_id);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void arch_restart() { sys_reboot(SYS_REBOOT_COLD); }
|
||||||
|
|
||||||
|
} // namespace esphome
|
||||||
|
|
||||||
|
void setup();
|
||||||
|
void loop();
|
||||||
|
|
||||||
|
int main() {
|
||||||
|
setup();
|
||||||
|
while (1) {
|
||||||
|
loop();
|
||||||
|
esphome::yield();
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
@@ -1,11 +1,10 @@
|
|||||||
#ifdef USE_NRF52
|
|
||||||
#ifdef USE_ZEPHYR
|
#ifdef USE_ZEPHYR
|
||||||
#include "gpio.h"
|
#include "gpio.h"
|
||||||
#include "esphome/core/log.h"
|
#include "esphome/core/log.h"
|
||||||
#include <zephyr/drivers/gpio.h>
|
#include <zephyr/drivers/gpio.h>
|
||||||
|
|
||||||
namespace esphome {
|
namespace esphome {
|
||||||
namespace nrf52 {
|
namespace zephyr {
|
||||||
|
|
||||||
static const char *const TAG = "nrf52";
|
static const char *const TAG = "nrf52";
|
||||||
|
|
||||||
@@ -109,7 +108,7 @@ void NRF52GPIOPin::detach_interrupt() const {
|
|||||||
// TODO
|
// TODO
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace nrf52
|
} // namespace zephyr
|
||||||
|
|
||||||
bool IRAM_ATTR ISRInternalGPIOPin::digital_read() {
|
bool IRAM_ATTR ISRInternalGPIOPin::digital_read() {
|
||||||
// TODO
|
// TODO
|
||||||
@@ -119,4 +118,3 @@ bool IRAM_ATTR ISRInternalGPIOPin::digital_read() {
|
|||||||
} // namespace esphome
|
} // namespace esphome
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
#endif // USE_NRF52
|
|
37
esphome/components/zephyr/gpio.h
Normal file
37
esphome/components/zephyr/gpio.h
Normal file
@@ -0,0 +1,37 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#ifdef USE_ZEPHYR
|
||||||
|
#include "esphome/core/hal.h"
|
||||||
|
struct device;
|
||||||
|
namespace esphome {
|
||||||
|
namespace zephyr {
|
||||||
|
|
||||||
|
class NRF52GPIOPin : public InternalGPIOPin {
|
||||||
|
public:
|
||||||
|
void set_pin(uint8_t pin) { pin_ = pin; }
|
||||||
|
void set_inverted(bool inverted) { inverted_ = inverted; }
|
||||||
|
void set_flags(gpio::Flags flags) { flags_ = flags; }
|
||||||
|
|
||||||
|
void setup() override;
|
||||||
|
void pin_mode(gpio::Flags flags) override;
|
||||||
|
bool digital_read() override;
|
||||||
|
void digital_write(bool value) override;
|
||||||
|
std::string dump_summary() const override;
|
||||||
|
void detach_interrupt() const override;
|
||||||
|
ISRInternalGPIOPin to_isr() const override;
|
||||||
|
uint8_t get_pin() const override { return pin_; }
|
||||||
|
bool is_inverted() const override { return inverted_; }
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void attach_interrupt(void (*func)(void *), void *arg, gpio::InterruptType type) const override;
|
||||||
|
uint8_t pin_;
|
||||||
|
bool inverted_;
|
||||||
|
gpio::Flags flags_;
|
||||||
|
const device *gpio_ = nullptr;
|
||||||
|
bool value_ = false;
|
||||||
|
};
|
||||||
|
|
||||||
|
} // namespace zephyr
|
||||||
|
} // namespace esphome
|
||||||
|
|
||||||
|
#endif // USE_ZEPHYR
|
@@ -24,7 +24,7 @@ template<int... S> struct gens<0, S...> { using type = seq<S...>; }; // NOLINT
|
|||||||
|
|
||||||
template<typename T, typename... X> class TemplatableValue {
|
template<typename T, typename... X> class TemplatableValue {
|
||||||
public:
|
public:
|
||||||
TemplatableValue() : type_(EMPTY) {}
|
TemplatableValue() : type_(ESPHOME_EMPTY) {}
|
||||||
|
|
||||||
template<typename F, enable_if_t<!is_invocable<F, X...>::value, int> = 0>
|
template<typename F, enable_if_t<!is_invocable<F, X...>::value, int> = 0>
|
||||||
TemplatableValue(F value) : type_(VALUE), value_(value) {}
|
TemplatableValue(F value) : type_(VALUE), value_(value) {}
|
||||||
@@ -32,7 +32,7 @@ template<typename T, typename... X> class TemplatableValue {
|
|||||||
template<typename F, enable_if_t<is_invocable<F, X...>::value, int> = 0>
|
template<typename F, enable_if_t<is_invocable<F, X...>::value, int> = 0>
|
||||||
TemplatableValue(F f) : type_(LAMBDA), f_(f) {}
|
TemplatableValue(F f) : type_(LAMBDA), f_(f) {}
|
||||||
|
|
||||||
bool has_value() { return this->type_ != EMPTY; }
|
bool has_value() { return this->type_ != ESPHOME_EMPTY; }
|
||||||
|
|
||||||
T value(X... x) {
|
T value(X... x) {
|
||||||
if (this->type_ == LAMBDA) {
|
if (this->type_ == LAMBDA) {
|
||||||
@@ -58,7 +58,7 @@ template<typename T, typename... X> class TemplatableValue {
|
|||||||
|
|
||||||
protected:
|
protected:
|
||||||
enum {
|
enum {
|
||||||
EMPTY,
|
ESPHOME_EMPTY,
|
||||||
VALUE,
|
VALUE,
|
||||||
LAMBDA,
|
LAMBDA,
|
||||||
} type_;
|
} type_;
|
||||||
|
@@ -54,6 +54,9 @@
|
|||||||
#endif
|
#endif
|
||||||
#include "esphome/components/nrf52/core.h"
|
#include "esphome/components/nrf52/core.h"
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef USE_ZEPHYR
|
||||||
|
#include <zephyr/random/rand32.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
namespace esphome {
|
namespace esphome {
|
||||||
|
|
||||||
@@ -248,12 +251,11 @@ bool random_bytes(uint8_t *data, size_t len) {
|
|||||||
}
|
}
|
||||||
fclose(fp);
|
fclose(fp);
|
||||||
return true;
|
return true;
|
||||||
#elif defined(USE_NRF52)
|
#elif defined(USE_NRF52) && defined(USE_ARDUINO)
|
||||||
#ifdef USE_ARDUINO
|
|
||||||
return nRFCrypto.Random.generate(data, len);
|
return nRFCrypto.Random.generate(data, len);
|
||||||
#elif USE_ZEPHYR
|
#elif defined(USE_ZEPHYR)
|
||||||
// TODO
|
sys_rand_get(data, len);
|
||||||
#endif
|
return true;
|
||||||
#else
|
#else
|
||||||
#error "No random source available for this configuration."
|
#error "No random source available for this configuration."
|
||||||
#endif
|
#endif
|
||||||
@@ -525,14 +527,18 @@ void hsv_to_rgb(int hue, float saturation, float value, float &red, float &green
|
|||||||
}
|
}
|
||||||
|
|
||||||
// System APIs
|
// System APIs
|
||||||
#if defined(USE_ESP8266) || defined(USE_RP2040) || defined(USE_HOST) || defined(USE_NRF52)
|
#if defined(USE_ESP8266) || defined(USE_RP2040) || defined(USE_HOST)
|
||||||
// ESP8266 doesn't have mutexes, but that shouldn't be an issue as it's single-core and non-preemptive OS.
|
// ESP8266 doesn't have mutexes, but that shouldn't be an issue as it's single-core and non-preemptive OS.
|
||||||
Mutex::Mutex() {}
|
Mutex::Mutex() {}
|
||||||
void Mutex::lock() {}
|
void Mutex::lock() {}
|
||||||
bool Mutex::try_lock() { return true; }
|
bool Mutex::try_lock() { return true; }
|
||||||
void Mutex::unlock() {}
|
void Mutex::unlock() {}
|
||||||
// TODO
|
#elif defined(USE_ZEPHYR)
|
||||||
#elif defined(USE_ESP32) || defined(USE_LIBRETINY) /*|| defined(USE_NRF52)*/
|
Mutex::Mutex() { k_mutex_init(&handle_); }
|
||||||
|
void Mutex::lock() { k_mutex_lock(&this->handle_, K_FOREVER); }
|
||||||
|
bool Mutex::try_lock() { return k_mutex_lock(&this->handle_, K_NO_WAIT) == 0; }
|
||||||
|
void Mutex::unlock() { k_mutex_unlock(&this->handle_); }
|
||||||
|
#elif defined(USE_ESP32) || defined(USE_LIBRETINY) || defined(USE_NRF52)
|
||||||
Mutex::Mutex() { handle_ = xSemaphoreCreateMutex(); }
|
Mutex::Mutex() { handle_ = xSemaphoreCreateMutex(); }
|
||||||
void Mutex::lock() { xSemaphoreTake(this->handle_, portMAX_DELAY); }
|
void Mutex::lock() { xSemaphoreTake(this->handle_, portMAX_DELAY); }
|
||||||
bool Mutex::try_lock() { return xSemaphoreTake(this->handle_, 0) == pdTRUE; }
|
bool Mutex::try_lock() { return xSemaphoreTake(this->handle_, 0) == pdTRUE; }
|
||||||
|
@@ -21,10 +21,10 @@
|
|||||||
#elif defined(USE_LIBRETINY)
|
#elif defined(USE_LIBRETINY)
|
||||||
#include <FreeRTOS.h>
|
#include <FreeRTOS.h>
|
||||||
#include <semphr.h>
|
#include <semphr.h>
|
||||||
#elif defined(USE_NRF52)
|
#elif defined(USE_NRF52) && defined(USE_ARDUINO)
|
||||||
#ifdef USE_ARDUINO
|
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
#endif
|
#elif defined(USE_ZEPHYR)
|
||||||
|
#include <zephyr/kernel.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define HOT __attribute__((hot))
|
#define HOT __attribute__((hot))
|
||||||
@@ -551,8 +551,9 @@ class Mutex {
|
|||||||
Mutex &operator=(const Mutex &) = delete;
|
Mutex &operator=(const Mutex &) = delete;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
// TODO
|
#if defined(USE_ZEPHYR)
|
||||||
#if defined(USE_ESP32) || defined(USE_LIBRETINY) /*|| defined(USE_NRF52)*/
|
k_mutex handle_;
|
||||||
|
#elif defined(USE_ESP32) || defined(USE_LIBRETINY) || defined(USE_NRF52)
|
||||||
SemaphoreHandle_t handle_;
|
SemaphoreHandle_t handle_;
|
||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
Reference in New Issue
Block a user