Compare commits

..

No commits in common. "a8fd6927af4bad6c365802cda16019df12398e7a" and "506c8409333d92256564f8d6cc0d9d0d243bb742" have entirely different histories.

20 changed files with 1139 additions and 1407 deletions

View File

@ -21,7 +21,7 @@ dependencies:
rules:
- if: "target == esp32s3"
jgromes/radiolib:
version: "7.3.0"
version: "7.2.1"
rules:
- if: "target in [esp32s3, esp32p4]"

View File

@ -25,7 +25,7 @@ static DeviceVector createDevices() {
auto sx1262 = std::make_shared<Sx1262>(Sx1262::Configuration{
.spiHostDevice = SPI2_HOST,
.spiFrequency = 4'000'000,
.spiFrequency = 10'000'000,
.csPin = GPIO_NUM_36,
.resetPin = GPIO_NUM_47,
.busyPin = GPIO_NUM_48,

View File

@ -1,70 +0,0 @@
#include "LevelInterruptHandler.h"
#include <esp_attr.h>
void IRAM_ATTR LevelInterruptHandler::handlePositiveEdge(void* isr_arg) {
LevelInterruptHandler* self = static_cast<LevelInterruptHandler*>(isr_arg);
switch (self->state) {
case State::Low:
gpio_set_intr_type(self->pin, GPIO_INTR_HIGH_LEVEL);
self->state = State::High;
break;
case State::High:
gpio_set_intr_type(self->pin, GPIO_INTR_LOW_LEVEL);
self->isr(self->context);
self->state = State::Low;
break;
}
}
void IRAM_ATTR LevelInterruptHandler::handleNegativeEdge(void* isr_arg) {
LevelInterruptHandler* self = static_cast<LevelInterruptHandler*>(isr_arg);
switch (self->state) {
case State::High:
gpio_set_intr_type(self->pin, GPIO_INTR_LOW_LEVEL);
self->state = State::Low;
break;
case State::Low:
gpio_set_intr_type(self->pin, GPIO_INTR_HIGH_LEVEL);
self->isr(self->context);
self->state = State::High;
break;
}
}
void IRAM_ATTR LevelInterruptHandler::handleOneshot(void* isr_arg) {
LevelInterruptHandler* self = static_cast<LevelInterruptHandler*>(isr_arg);
gpio_intr_disable(self->pin);
self->isr(self->context);
}
void LevelInterruptHandler::install() {
switch (type) {
case Type::HighOneshot:
gpio_set_intr_type(pin, GPIO_INTR_HIGH_LEVEL);
gpio_isr_handler_add(pin, handleOneshot, this);
break;
case Type::LowOneshot:
gpio_set_intr_type(pin, GPIO_INTR_LOW_LEVEL);
gpio_isr_handler_add(pin, handleOneshot, this);
break;
case Type::PositiveEdge:
gpio_set_intr_type(pin, GPIO_INTR_LOW_LEVEL);
gpio_isr_handler_add(pin, handlePositiveEdge, this);
state = State::Low;
break;
case Type::NegativeEdge:
gpio_set_intr_type(pin, GPIO_INTR_HIGH_LEVEL);
gpio_isr_handler_add(pin, handleNegativeEdge, this);
state = State::High;
break;
}
}
void LevelInterruptHandler::arm() {
gpio_intr_enable(pin);
}
void LevelInterruptHandler::disarm() {
gpio_intr_disable(pin);
}

View File

@ -1,56 +0,0 @@
#pragma once
#include <driver/gpio.h>
/**
* An interrupt handler class which can trigger any given IRAM service routine
* for falling/rising edge level changes and oneshot level detection.
* This class is needed if the erratum 3.11 from ESP32 Series SoC Errata Version v2.9 applies.
* In short, once an edge sensitive interrupt is installed, subsequent interrupts may not work.
* This class uses high/low level interrupts to handle both edge detection and oneshot detection of levels
* which circumvents this problem.
*/
class LevelInterruptHandler {
public:
enum class Type {
HighOneshot,
LowOneshot,
PositiveEdge,
NegativeEdge
};
using ServiceRoutine = void(*)(void* ctx);
private:
enum class State {
Low,
High
};
const gpio_num_t pin;
const Type type;
const ServiceRoutine isr;
void* context;
State state;
static void handlePositiveEdge(void* isr_arg);
static void handleNegativeEdge(void* isr_arg);
static void handleOneshot(void* isr_arg);
public:
LevelInterruptHandler(const gpio_num_t pin, const Type type, ServiceRoutine isr, void* context)
: pin(pin)
, type(type)
, isr(isr)
, context(context)
{}
virtual ~LevelInterruptHandler() {
disarm();
}
void install();
void arm();
void disarm();
};

View File

@ -1,17 +1,17 @@
#include "RadiolibTactilityHal.h"
#include <Tactility/kernel/Kernel.h>
#include "hal/gpio_hal.h"
#include "esp_timer.h"
constexpr const char* TAG = "RadiolibTactilityHal";
void RadiolibTactilityHal::init() {
// we only need to init the SPI here
spiBegin();
}
void RadiolibTactilityHal::term() {
// we only need to stop the SPI here
spiEnd();
}
@ -24,7 +24,7 @@ void RadiolibTactilityHal::pinMode(uint32_t pin, uint32_t mode) {
gpiohal.dev = GPIO_LL_GET_HW(GPIO_PORT_0);
gpio_config_t conf = {
.pin_bit_mask = (1ULL << pin),
.pin_bit_mask = (1ULL<<pin),
.mode = (gpio_mode_t)mode,
.pull_up_en = GPIO_PULLUP_DISABLE,
.pull_down_en = GPIO_PULLDOWN_DISABLE,
@ -43,34 +43,61 @@ void RadiolibTactilityHal::digitalWrite(uint32_t pin, uint32_t value) {
uint32_t RadiolibTactilityHal::digitalRead(uint32_t pin) {
if(pin == RADIOLIB_NC) {
return 0;
return(0);
}
return gpio_get_level((gpio_num_t)pin);
return(gpio_get_level((gpio_num_t)pin));
}
void RadiolibTactilityHal::attachInterrupt(uint32_t interruptNum, void (*interruptCb)(void), uint32_t mode) {
TT_LOG_E(TAG, "Interrupt registration via RadioLib is not supported!");
if(interruptNum == RADIOLIB_NC) {
return;
}
if (!isrServiceInitialized) {
gpio_install_isr_service((int)ESP_INTR_FLAG_IRAM);
isrServiceInitialized = true;
}
gpio_set_intr_type((gpio_num_t)interruptNum, (gpio_int_type_t)(mode & 0x7));
// this uses function typecasting, which is not defined when the functions have different signatures
// untested and might not work
// TODO: I think the wisest course of action is forbidding registration via RadioLib entirely,
// as it doesn't suit Tactility with its lack of context passing
gpio_isr_handler_add((gpio_num_t)interruptNum, (void (*)(void*))interruptCb, NULL);
}
void RadiolibTactilityHal::detachInterrupt(uint32_t interruptNum) {
TT_LOG_E(TAG, "Interrupt registration via RadioLib is not supported!");
if(interruptNum == RADIOLIB_NC) {
return;
}
gpio_isr_handler_remove((gpio_num_t)interruptNum);
gpio_wakeup_disable((gpio_num_t)interruptNum);
gpio_set_intr_type((gpio_num_t)interruptNum, GPIO_INTR_DISABLE);
}
void RadiolibTactilityHal::delay(unsigned long ms) {
tt::kernel::delayMillis(ms);
vTaskDelay(ms / portTICK_PERIOD_MS);
}
void RadiolibTactilityHal::delayMicroseconds(unsigned long us) {
tt::kernel::delayMicros(us);
uint64_t m = (uint64_t)esp_timer_get_time();
if(us) {
uint64_t e = (m + us);
if(m > e) { // overflow
while((uint64_t)esp_timer_get_time() > e);
}
while((uint64_t)esp_timer_get_time() < e);
}
}
unsigned long RadiolibTactilityHal::millis() {
return (unsigned long)(esp_timer_get_time() / 1000ULL);
return((unsigned long)(esp_timer_get_time() / 1000ULL));
}
unsigned long RadiolibTactilityHal::micros() {
return (unsigned long)(esp_timer_get_time());
return((unsigned long)(esp_timer_get_time()));
}
long RadiolibTactilityHal::pulseIn(uint32_t pin, uint32_t state, unsigned long timeout) {
@ -84,46 +111,52 @@ long RadiolibTactilityHal::pulseIn(uint32_t pin, uint32_t state, unsigned long t
while(this->digitalRead(pin) == state) {
if((this->micros() - curtick) > timeout) {
return 0;
return(0);
}
}
return (this->micros() - start);
return(this->micros() - start);
}
void RadiolibTactilityHal::spiBegin() {
if (!spiInitialized) {
TT_LOG_I(TAG, "SPI Begin!");
spi_device_interface_config_t devcfg = {};
devcfg.clock_speed_hz = spiFrequency;
devcfg.mode = 0;
// CS is set to unused, as RadioLib sets it manually
devcfg.spics_io_num = -1;
devcfg.spics_io_num = csPin;
devcfg.queue_size = 1;
esp_err_t ret = spi_bus_add_device(spiHostDevice, &devcfg, &spiDeviceHandle);
if (ret != ESP_OK) {
TT_LOG_E(TAG, "Failed to add SPI device, error %s", esp_err_to_name(ret));
TT_LOG_E(TAG, "Failed to add SPI device: %s", esp_err_to_name(ret));
}
spiInitialized = true;
}
}
void RadiolibTactilityHal::spiBeginTransaction() {
getLock()->lock();
spi_device_acquire_bus(spiDeviceHandle, portMAX_DELAY);
// This function is used to set up the transaction (speed, bit order, mode, ...).
// With the ESP-IDF HAL this is automatically done, so no code needed.
}
void RadiolibTactilityHal::spiTransfer(uint8_t* out, size_t len, uint8_t* in) {
spi_transaction_t t;
memset(&t, 0, sizeof(t));
t.length = len * 8;
t.tx_buffer = out;
t.rx_buffer = in;
auto lock = getLock()->asScopedLock();
bool locked = lock.lock(portMAX_DELAY);
if (!locked) {
TT_LOG_E(TAG, "Failed to aquire SPI lock");
}
memset(&t, 0, sizeof(t)); // Zero out the transaction
t.length = len * 8; // Length is in bits
t.tx_buffer = out; // The data to send
t.rx_buffer = in; // The data to receive
spi_device_polling_transmit(spiDeviceHandle, &t);
}
void RadiolibTactilityHal::spiEndTransaction() {
spi_device_release_bus(spiDeviceHandle);
getLock()->unlock();
// nothing needs to be done here
}
void RadiolibTactilityHal::spiEnd() {

View File

@ -17,12 +17,14 @@ class RadiolibTactilityHal : public RadioLibHal {
private:
spi_host_device_t spiHostDevice;
int spiFrequency;
gpio_num_t csPin;
spi_device_handle_t spiDeviceHandle;
std::shared_ptr<tt::Lock> lock;
bool spiInitialized;
bool isrServiceInitialized;
public:
explicit RadiolibTactilityHal(spi_host_device_t spiHostDevice, int spiFrequency)
explicit RadiolibTactilityHal(spi_host_device_t spiHostDevice, int spiFrequency, gpio_num_t csPin)
: RadioLibHal(
GPIO_MODE_INPUT,
GPIO_MODE_OUTPUT,
@ -32,8 +34,10 @@ public:
GPIO_INTR_NEGEDGE)
, spiHostDevice(spiHostDevice)
, spiFrequency(spiFrequency)
, csPin(csPin)
, lock(tt::hal::spi::getLock(spiHostDevice))
, spiInitialized(false) {}
, spiInitialized(false)
, isrServiceInitialized(false) {}
void init() override;
void term() override;

View File

@ -68,14 +68,13 @@ bool RadiolibThreadedDevice::isThreadInterrupted() const {
int32_t RadiolibThreadedDevice::threadMain() {
int rc = doBegin(getModulation());
bool hasRx = false;
if (rc != 0) {
return rc;
}
setState(State::On);
while (!isThreadInterrupted()) {
hasRx = doListen();
doListen();
// Thread might've been interrupted in the meanwhile
if (isThreadInterrupted()) {
@ -85,9 +84,7 @@ int32_t RadiolibThreadedDevice::threadMain() {
if (getTxQueueSize() > 0) {
doTransmit();
} else {
if (hasRx) {
doReceive();
}
doReceive();
}
}

View File

@ -20,7 +20,7 @@ protected:
virtual int doBegin(const Modulation modulation) = 0;
virtual void doEnd() = 0;
virtual void doTransmit() = 0;
virtual bool doListen() = 0;
virtual void doListen() = 0;
virtual void doReceive() = 0;
public:

View File

@ -32,9 +32,8 @@ static constexpr Sx1262::ParameterStatus checkValuesAndApply(T &target, const fl
return Sx1262::ParameterStatus::ValueError;
}
void IRAM_ATTR Sx1262::dio1Isr(void* ctx) {
GPIO.out_w1ts = 1 << 9;
static_cast<Sx1262*>(ctx)->dio1Event();
void IRAM_ATTR dio1handler(void* context) {
((Sx1262*)context)->dio1Event();
}
Sx1262::ParameterStatus Sx1262::setBaseParameter(const Parameter parameter, const float value) {
@ -292,38 +291,35 @@ tt::hal::radio::Unit Sx1262::getParameterUnit(const Parameter parameter) const {
}
void Sx1262::registerDio1Isr() {
gpio_hal_context_t gpiohal;
gpiohal.dev = GPIO_LL_GET_HW(GPIO_PORT_0);
gpio_config_t conf = {
.pin_bit_mask = (1ULL << configuration.irqPin),
.pin_bit_mask = (1ULL<<configuration.irqPin),
.mode = (gpio_mode_t)GPIO_MODE_INPUT,
.pull_up_en = GPIO_PULLUP_DISABLE,
.pull_down_en = GPIO_PULLDOWN_DISABLE,
.intr_type = GPIO_INTR_DISABLE,
};
gpio_config(&conf);
// TODO: Debug Code - Remove
conf = {
.pin_bit_mask = (1ULL<<GPIO_NUM_9),
.mode = (gpio_mode_t)GPIO_MODE_OUTPUT,
.pull_up_en = GPIO_PULLUP_DISABLE,
.pull_down_en = GPIO_PULLDOWN_ENABLE
.pull_down_en = GPIO_PULLDOWN_ENABLE,
.intr_type = (gpio_int_type_t)gpiohal.dev->pin[configuration.irqPin].int_type,
};
gpio_config(&conf);
interrupt.install();
interrupt.arm();
// We cannot use the RadioLib API to register this action,
// as it does not have the capability to pass an instance pointer via context.
// A trampoline has been tried, but is not linkable to be in IRAM_ATTR (dangerous relocation).
gpio_install_isr_service((int)ESP_INTR_FLAG_IRAM);
gpio_set_intr_type(configuration.irqPin, GPIO_INTR_POSEDGE);
gpio_isr_handler_add(configuration.irqPin, dio1handler, this);
}
void Sx1262::unregisterDio1Isr() {
interrupt.disarm();
}
void Sx1262::armDio1Irq() {
gpio_set_level(GPIO_NUM_9, 0);
gpio_isr_handler_remove(configuration.irqPin);
gpio_wakeup_disable(configuration.irqPin);
gpio_set_intr_type(configuration.irqPin, GPIO_INTR_DISABLE);
}
void IRAM_ATTR Sx1262::dio1Event() {
static const auto DRAM_ATTR bit = SX1262_DIO1_EVENT_BIT;
auto f = events.set(bit);
events.set(bit);
}
void Sx1262::txQueuedSignal() {
@ -400,7 +396,7 @@ void Sx1262::doTransmit() {
uint16_t rc = RADIOLIB_ERR_NONE;
rc = radio.standby();
if (rc != RADIOLIB_ERR_NONE) {
TT_LOG_W(TAG, "RadioLib returned %hi on TX standby", rc);
TT_LOG_W(TAG, "RadioLib returned %hi on standby", rc);
}
if (getModulation() == Modulation::Fsk) {
@ -416,9 +412,6 @@ void Sx1262::doTransmit() {
auto txEventFlags = events.wait(SX1262_INTERRUPT_BIT | SX1262_DIO1_EVENT_BIT, tt::EventFlag::WaitAny,
pdMS_TO_TICKS(SX1262_TX_TIMEOUT_MILLIS));
// Clean up after transmission
radio.finishTransmit();
// Thread might've been interrupted in the meanwhile
if (isThreadInterrupted()) {
return;
@ -437,40 +430,23 @@ void Sx1262::doTransmit() {
}
}
bool Sx1262::doListen() {
uint16_t rc = RADIOLIB_ERR_NONE;
void Sx1262::doListen() {
if (getModulation() != Modulation::LrFhss) {
armDio1Irq();
rc = radio.startReceiveDutyCycleAuto(preambleLength, 0, SX1262_IRQ_FLAGS);
if (rc == RADIOLIB_ERR_NONE) {
auto flags = events.wait(SX1262_INTERRUPT_BIT | SX1262_DIO1_EVENT_BIT | SX1262_QUEUED_TX_BIT);
return (flags & SX1262_DIO1_EVENT_BIT) != 0;
} else {
TT_LOG_E(TAG, "Error setting dutycycle RX, RadioLib returned %hi", rc);
}
return false;
radio.startReceive();
events.wait(SX1262_INTERRUPT_BIT | SX1262_DIO1_EVENT_BIT | SX1262_QUEUED_TX_BIT);
} else {
// LR-FHSS modem only supports TX
events.wait(SX1262_INTERRUPT_BIT | SX1262_QUEUED_TX_BIT);
return false;
}
}
void Sx1262::doReceive() {
uint16_t rc = RADIOLIB_ERR_NONE;
// LR-FHSS modem only supports TX
if (getModulation() == Modulation::LrFhss) return;
/*
rc = radio.standby();
if (rc != RADIOLIB_ERR_NONE) {
TT_LOG_W(TAG, "RadioLib returned %hi on TX standby", rc);
}*/
uint16_t rxSize = radio.getPacketLength(true);
std::vector<uint8_t> data(rxSize);
rc = radio.readData(data.data(), rxSize);
uint16_t rc = radio.readData(data.data(), rxSize);
if (rc != RADIOLIB_ERR_NONE) {
TT_LOG_E(TAG, "Error receiving data, RadioLib returned %hi", rc);
} else if(rxSize == 0) {
@ -487,10 +463,9 @@ void Sx1262::doReceive() {
};
publishRx(rxPacket);
radio.finishReceive();
}
// A delay before a new command improves reliability
//vTaskDelay(pdMS_TO_TICKS(SX1262_COOLDOWN_MILLIS));
vTaskDelay(pdMS_TO_TICKS(SX1262_COOLDOWN_MILLIS));
}

View File

@ -7,7 +7,6 @@
#include <RadioLib.h>
#include "RadiolibTactilityHal.h"
#include "RadiolibThreadedDevice.h"
#include "LevelInterruptHandler.h"
#include <utility>
@ -28,22 +27,21 @@ public:
private:
static constexpr auto SX1262_DEFAULT_NAME = "SX1262";
static constexpr auto SX1262_COOLDOWN_MILLIS = 100;
static constexpr auto SX1262_RX_TIMEOUT_MILLIS = 10'000;
static constexpr auto SX1262_TX_TIMEOUT_MILLIS = 2000;
static constexpr auto SX1262_INTERRUPT_BIT = BIT0;
static constexpr auto SX1262_DIO1_EVENT_BIT = BIT1;
static constexpr auto SX1262_QUEUED_TX_BIT = BIT2;
static constexpr auto SX1262_IRQ_FLAGS = (RADIOLIB_IRQ_RX_DEFAULT_FLAGS);
const Configuration configuration;
LevelInterruptHandler interrupt;
std::string name;
const Configuration configuration;
std::shared_ptr<tt::Lock> lock;
tt::EventFlag events;
RadiolibTactilityHal hal;
Module radioModule;
SX1262 radio;
TxItem currentTx;
// Shared parameters which have a common lowest value are set here
int8_t power = -9.0;
float frequency = 150;
float bandwidth = 0.0;
@ -58,7 +56,6 @@ private:
void registerDio1Isr();
void unregisterDio1Isr();
void armDio1Irq();
ParameterStatus setBaseParameter(const Parameter parameter, const float value);
ParameterStatus setLoraParameter(const Parameter parameter, const float value);
@ -71,33 +68,30 @@ private:
protected:
static void dio1Isr(void* ctx);
virtual void txQueuedSignal() override;
virtual void interruptSignal() override;
virtual int doBegin(const Modulation modulation) override;
virtual void doEnd() override;
virtual void doTransmit() override;
virtual bool doListen() override;
virtual void doListen() override;
virtual void doReceive() override;
public:
explicit Sx1262(const Configuration& configuration, const std::string& name = SX1262_DEFAULT_NAME)
: RadiolibThreadedDevice(name, 4096)
, configuration(configuration)
, interrupt(configuration.irqPin, LevelInterruptHandler::Type::PositiveEdge, dio1Isr, this)
, name(name)
, hal(configuration.spiHostDevice, configuration.spiFrequency)
, radioModule(&hal, configuration.csPin, RADIOLIB_NC, configuration.resetPin, configuration.busyPin)
, configuration(configuration)
, hal(configuration.spiHostDevice, configuration.spiFrequency, configuration.csPin)
, radioModule(&hal, configuration.csPin, configuration.irqPin, configuration.resetPin, configuration.busyPin)
, radio(&radioModule)
{}
~Sx1262() override = default;
std::string getName() const override { return name; }
std::string getDescription() const override { return "Semtech SX1262 LoRa and (G)FSK capable radio"; }
std::string getDescription() const override { return "Semtech SX1262 LoRa, FSK and LR-FHSS capable radio"; }
ParameterStatus setParameter(const Parameter parameter, const float value) override;
ParameterStatus getParameter(const Parameter parameter, float &value) const override;

View File

@ -1,7 +1,5 @@
#pragma once
#include <cassert>
template <typename DataType>
class LinkedList {

File diff suppressed because it is too large Load Diff

View File

@ -1,18 +1,13 @@
#pragma once
#include "SettingsView.h"
#include "TermView.h"
#include "tt_app.h"
#include "tt_hal_radio.h"
#include <lvgl.h>
class RadioSet {
enum class View {
Terminal,
Settings
};
class TermView;
class SettingsView;
class RadioSet {
lv_obj_t* mainView = nullptr;
lv_obj_t* uiDropDownMenu = nullptr;
lv_obj_t* progressBar = nullptr;
@ -26,6 +21,4 @@ public:
~RadioSet();
void onShow(AppHandle context, lv_obj_t* parent);
void showView(View view);
};

View File

@ -1,893 +0,0 @@
#include "SettingsView.h"
#include "Utils.h"
static lv_obj_t* createGridDropdownInput(lv_obj_t *container, int row, const char* const label, const char* const items) {
lv_obj_t* label_obj = lv_label_create(container);
lv_label_set_text(label_obj, label);
lv_obj_set_grid_cell(label_obj,
LV_GRID_ALIGN_STRETCH, 0, 1,
LV_GRID_ALIGN_CENTER, row, 1);
lv_obj_set_size(label_obj, lv_pct(100), LV_SIZE_CONTENT);
lv_obj_t* input = lv_dropdown_create(container);
lv_obj_set_grid_cell(input,
LV_GRID_ALIGN_STRETCH, 1, 1,
LV_GRID_ALIGN_CENTER, row, 1);
lv_obj_set_size(input, lv_pct(100), LV_SIZE_CONTENT);
lv_dropdown_set_options(input, items);
return input;
}
struct ParameterInput {
static constexpr auto LV_STATE_INVALID = LV_STATE_USER_1;
typedef void (*Callback)(void* ctx);
const RadioHandle handle;
const RadioParameter param;
Callback userChangeCallback = nullptr;
void* userChangeCtx = nullptr;
static void apply_error_style(lv_obj_t* obj) {
static bool init = false;
static lv_style_t style_invalid;
if (!init) {
lv_style_init(&style_invalid);
lv_style_set_border_color(&style_invalid, lv_color_hex(0xFFBF00));
lv_style_set_border_width(&style_invalid, 2);
init = true;
}
lv_obj_add_style(obj, &style_invalid, LV_STATE_INVALID);
}
ParameterInput(RadioHandle handle, const RadioParameter param)
: handle(handle)
, param(param) {}
virtual ~ParameterInput() = default;
void onUserChange(Callback cb, void* ctx) {
userChangeCallback = cb;
userChangeCtx = ctx;
}
void emitUserChange() {
if (userChangeCallback) {
userChangeCallback(userChangeCtx);
}
}
virtual void storeToRadio() = 0;
virtual void updatePreview() = 0;
virtual void activate() = 0;
virtual void deactivate() = 0;
virtual void setValue(float value) = 0;
};
struct NumericParameterInput : public ParameterInput {
lv_obj_t* label = nullptr;
lv_obj_t* input = nullptr;
lv_obj_t* unitlabel = nullptr;
char* fmt;
NumericParameterInput(RadioHandle handle, const RadioParameter param, lv_obj_t* container, int row, char* fmt = "%f", char* unit_override = nullptr)
: ParameterInput(handle, param)
, fmt(fmt) {
initUi(container, row, unit_override);
loadFromRadio();
}
virtual ~NumericParameterInput() {
//lv_obj_clean(label);
//lv_obj_clean(input);
//lv_obj_clean(unitlabel);
}
void initUi(lv_obj_t* container, int row, char* unit_override) {
const int height = LV_SIZE_CONTENT;
label = lv_label_create(container);
lv_label_set_text(label, toString(param));
lv_obj_set_grid_cell(label,
LV_GRID_ALIGN_STRETCH, 0, 1,
LV_GRID_ALIGN_CENTER, row, 1);
lv_obj_set_size(label, lv_pct(100), height);
input = lv_textarea_create(container);
lv_obj_set_grid_cell(input,
LV_GRID_ALIGN_STRETCH, 1, 1,
LV_GRID_ALIGN_CENTER, row, 1);
lv_obj_set_size(input, lv_pct(100), height);
lv_textarea_set_accepted_chars(input, "0123456789.+-");
loadFromRadio();
lv_textarea_set_one_line(input, true);
apply_error_style(input);
unitlabel = lv_label_create(container);
lv_obj_set_grid_cell(unitlabel,
LV_GRID_ALIGN_STRETCH, 2, 1,
LV_GRID_ALIGN_CENTER, row, 1);
lv_obj_set_size(unitlabel, lv_pct(100), height);
lv_obj_set_style_text_align(unitlabel , LV_TEXT_ALIGN_LEFT, 0);
if (unit_override) {
lv_label_set_text(unitlabel, unit_override);
} else {
char unit[64] = {0};
tt_hal_radio_get_parameter_unit_str(handle, param, unit, sizeof(unit));
lv_label_set_text(unitlabel, unit);
}
lv_obj_add_event_cb(input, [](lv_event_t * e) {
NumericParameterInput* self = (NumericParameterInput*)lv_event_get_user_data(e);
self->storeToRadio();
self->emitUserChange();
}, LV_EVENT_VALUE_CHANGED, this);
}
void loadFromRadio() {
float value;
if (tt_hal_radio_get_parameter(handle, param, &value) == RADIO_PARAM_SUCCESS) {
setValue(value);
}
}
virtual void storeToRadio() override {
float value;
if (sscanf(lv_textarea_get_text(input), "%f", &value) == 1) {
if (tt_hal_radio_set_parameter(handle, param, value) != RADIO_PARAM_SUCCESS) {
lv_obj_add_state(input, LV_STATE_INVALID);
} else {
lv_obj_clear_state(input, LV_STATE_INVALID);
}
} else {
lv_obj_add_state(input, LV_STATE_INVALID);
}
}
virtual void updatePreview() override {}
virtual void activate() override {
lv_obj_clear_state(input, LV_STATE_DISABLED);
}
virtual void deactivate() override {
lv_obj_add_state(input, LV_STATE_DISABLED);
}
virtual void setValue(float value) override {
Str txt;
txt.appendf(fmt, value);
lv_textarea_set_text(input, txt.c_str());
}
};
struct SliderParameterInput : public ParameterInput {
char* fmt = nullptr;
lv_obj_t* label = nullptr;
lv_obj_t* slider = nullptr;
lv_obj_t* preview = nullptr;
SliderParameterInput(RadioHandle handle, const RadioParameter param, lv_obj_t* container, int row, int min, int max, char* fmt = "%i")
: ParameterInput(handle, param)
, fmt(fmt) {
initUi(container, row, min, max);
}
virtual ~SliderParameterInput() {
//lv_obj_clean(label);
//lv_obj_clean(slider);
//lv_obj_clean(preview);
}
void initUi(lv_obj_t* container, int row, int min, int max) {
label = lv_label_create(container);
lv_label_set_text(label, toString(param));
lv_obj_set_grid_cell(label,
LV_GRID_ALIGN_STRETCH, 0, 1,
LV_GRID_ALIGN_CENTER, row, 1);
lv_obj_set_size(label, lv_pct(100), LV_SIZE_CONTENT);
slider = lv_slider_create(container);
lv_obj_set_grid_cell(slider,
LV_GRID_ALIGN_STRETCH, 1, 1,
LV_GRID_ALIGN_CENTER, row, 1);
lv_obj_set_size(slider, lv_pct(100), 10);
lv_slider_set_range(slider, min, max);
apply_error_style(slider);
preview = lv_label_create(container);
lv_obj_set_grid_cell(preview,
LV_GRID_ALIGN_STRETCH, 2, 1,
LV_GRID_ALIGN_CENTER, row, 1);
lv_obj_set_size(preview, lv_pct(100), LV_SIZE_CONTENT);
lv_obj_set_style_text_align(preview , LV_TEXT_ALIGN_LEFT, 0);
loadFromRadio();
lv_obj_add_event_cb(slider, [](lv_event_t * e) {
lv_obj_t* slider = lv_event_get_target_obj(e);
SliderParameterInput* self = (SliderParameterInput*)lv_event_get_user_data(e);
self->updatePreview();
self->storeToRadio();
self->emitUserChange();
}, LV_EVENT_VALUE_CHANGED, this);
}
void loadFromRadio() {
float value;
if (tt_hal_radio_get_parameter(handle, param, &value) == RADIO_PARAM_SUCCESS) {
setValue(value);
}
}
virtual void storeToRadio() override {
if (tt_hal_radio_set_parameter(handle, param, lv_slider_get_value(slider)) != RADIO_PARAM_SUCCESS) {
lv_obj_add_state(slider, LV_STATE_INVALID);
} else {
lv_obj_clear_state(slider, LV_STATE_INVALID);
}
}
virtual void updatePreview() override {
char buf[64] = {0};
lv_snprintf(buf, sizeof(buf), fmt, lv_slider_get_value(slider));
lv_label_set_text(preview, buf);
}
virtual void activate() override {
lv_obj_clear_state(slider, LV_STATE_DISABLED);
}
virtual void deactivate() override {
lv_obj_add_state(slider, LV_STATE_DISABLED);
}
virtual void setValue(float value) override {
lv_slider_set_value(slider, value, LV_ANIM_ON);
updatePreview();
}
};
struct SliderSelectParameterInput : public ParameterInput {
static constexpr float SELECT_END = -1;
const float* selections;
const size_t selectionsSize;
char unit[64] = {0};
char* fmt;
lv_obj_t* label = nullptr;
lv_obj_t* slider = nullptr;
lv_obj_t* preview = nullptr;
static constexpr size_t get_selection_num(const float selections[]) {
constexpr size_t MAX_SELECTIONS = 32;
if (selections) {
for (size_t i = 0; i < MAX_SELECTIONS; ++i) {
if (selections[i] == SELECT_END) {
return i;
}
}
}
return 0;
}
SliderSelectParameterInput(RadioHandle handle, const RadioParameter param, lv_obj_t* container, int row, const float selections[] = nullptr, char* fmt = "%f")
: ParameterInput(handle, param)
, selections(selections)
, selectionsSize(get_selection_num(selections))
, fmt(fmt) {
initUi(container, row);
}
virtual ~SliderSelectParameterInput() {
//lv_obj_clean(label);
//lv_obj_clean(slider);
//lv_obj_clean(preview);
}
int get_selection_index(const float value) {
for (int i = 0; i < selectionsSize; ++i) {
if (selections[i] == value) {
return i;
}
}
return 0;
}
void initUi(lv_obj_t* container, int row) {
label = lv_label_create(container);
lv_label_set_text(label, toString(param));
lv_obj_set_grid_cell(label,
LV_GRID_ALIGN_STRETCH, 0, 1,
LV_GRID_ALIGN_CENTER, row, 1);
lv_obj_set_size(label, lv_pct(100), LV_SIZE_CONTENT);
slider = lv_slider_create(container);
lv_obj_set_grid_cell(slider,
LV_GRID_ALIGN_STRETCH, 1, 1,
LV_GRID_ALIGN_CENTER, row, 1);
lv_obj_set_size(slider, lv_pct(100), 10);
lv_slider_set_range(slider, 0, selectionsSize - 1);
apply_error_style(slider);
preview = lv_label_create(container);
lv_obj_set_grid_cell(preview,
LV_GRID_ALIGN_STRETCH, 2, 1,
LV_GRID_ALIGN_CENTER, row, 1);
lv_obj_set_size(preview, lv_pct(100), LV_SIZE_CONTENT);
lv_obj_set_style_text_align(preview , LV_TEXT_ALIGN_LEFT, 0);
tt_hal_radio_get_parameter_unit_str(handle, param, unit, sizeof(unit));
loadFromRadio();
lv_obj_add_event_cb(slider, [](lv_event_t * e) {
lv_obj_t* slider = lv_event_get_target_obj(e);
SliderSelectParameterInput* self = (SliderSelectParameterInput*)lv_event_get_user_data(e);
self->updatePreview();
self->storeToRadio();
self->emitUserChange();
}, LV_EVENT_VALUE_CHANGED, this);
}
void loadFromRadio() {
float value;
if (tt_hal_radio_get_parameter(handle, param, &value) == RADIO_PARAM_SUCCESS) {
setValue(value);
}
}
virtual void storeToRadio() override {
if (tt_hal_radio_set_parameter(handle, param, selections[lv_slider_get_value(slider)]) != RADIO_PARAM_SUCCESS) {
lv_obj_add_state(slider, LV_STATE_INVALID);
} else {
lv_obj_clear_state(slider, LV_STATE_INVALID);
}
}
virtual void updatePreview() override {
Str text;
text.appendf(fmt, selections[lv_slider_get_value(slider)]);
text.append(unit);
lv_label_set_text(preview, text.c_str());
}
virtual void activate() override {
lv_obj_clear_state(slider, LV_STATE_DISABLED);
}
virtual void deactivate() override {
lv_obj_add_state(slider, LV_STATE_DISABLED);
}
virtual void setValue(float value) override {
lv_slider_set_value(slider, get_selection_index(value), LV_ANIM_ON);
updatePreview();
}
};
struct FlagParameterInput : public ParameterInput {
lv_obj_t* label = nullptr;
lv_obj_t* input = nullptr;
FlagParameterInput(RadioHandle handle, const RadioParameter param, lv_obj_t* container, int row)
: ParameterInput(handle, param) {
initUi(container, row);
}
virtual ~FlagParameterInput() {
//lv_obj_clean(label);
//lv_obj_clean(input);
}
void initUi(lv_obj_t* container, int row) {
label = lv_label_create(container);
lv_label_set_text(label, toString(param));
lv_obj_set_grid_cell(label,
LV_GRID_ALIGN_STRETCH, 0, 1,
LV_GRID_ALIGN_CENTER, row, 1);
lv_obj_set_size(label, lv_pct(100), LV_SIZE_CONTENT);
input = lv_switch_create(container);
lv_obj_set_grid_cell(input,
LV_GRID_ALIGN_STRETCH, 2, 1,
LV_GRID_ALIGN_CENTER, row, 1);
lv_obj_set_size(input, 30, 20);
apply_error_style(input);
loadFromRadio();
lv_obj_add_event_cb(input, [](lv_event_t * e) {
lv_obj_t* slider = lv_event_get_target_obj(e);
FlagParameterInput* self = (FlagParameterInput*)lv_event_get_user_data(e);
self->storeToRadio();
self->emitUserChange();
}, LV_EVENT_VALUE_CHANGED, this);
}
void loadFromRadio() {
float value;
if (tt_hal_radio_get_parameter(handle, param, &value) == RADIO_PARAM_SUCCESS) {
setValue(value);
}
}
virtual void storeToRadio() override {
float value = lv_obj_has_state(input, LV_STATE_CHECKED) ? 1.0 : 0.0;
if (tt_hal_radio_set_parameter(handle, param, value) != RADIO_PARAM_SUCCESS) {
lv_obj_add_state(input, LV_STATE_INVALID);
} else {
lv_obj_clear_state(input, LV_STATE_INVALID);
}
}
virtual void updatePreview() override {
}
virtual void activate() override {
lv_obj_clear_state(input, LV_STATE_DISABLED);
}
virtual void deactivate() override {
lv_obj_add_state(input, LV_STATE_DISABLED);
}
virtual void setValue(float value) override {
if (value != 0.0) {
lv_obj_add_state(input, LV_STATE_CHECKED);
} else {
lv_obj_clear_state(input, LV_STATE_CHECKED);
}
}
};
static ParameterInput* makeLoraInput(RadioHandle handle, const RadioParameter param, lv_obj_t* container, int row) {
static constexpr float bw_values[] = {7.8, 10.4, 15.6, 20.8, 31.25, 41.7, 62.5, 125.0, 250.0, 500.0, SliderSelectParameterInput::SELECT_END};
// LoRa is standardized, so we get to use fancy inputs
switch (param) {
case RADIO_BANDWIDTH:
return new SliderSelectParameterInput(handle, param, container, row, bw_values, "%.1f");
case RADIO_SPREADFACTOR:
return new SliderParameterInput(handle, param, container, row, 7, 12);
case RADIO_CODINGRATE:
return new SliderParameterInput(handle, param, container, row, 5, 8);
case RADIO_SYNCWORD:
return new SliderParameterInput(handle, param, container, row, 0, 255, "%02X");
case RADIO_PREAMBLES:
return new SliderParameterInput(handle, param, container, row, 0, 0xFFFF);
default:
return new NumericParameterInput(handle, param, container, row);
}
}
static ParameterInput* makeLrFhssInput(RadioHandle handle, const RadioParameter param, lv_obj_t* container, int row) {
switch (param) {;
case RADIO_NARROWGRID:
return new FlagParameterInput(handle, param, container, row);
default:
return new NumericParameterInput(handle, param, container, row);
}
}
static ParameterInput* makeBaseInput(RadioHandle handle, const RadioParameter param, lv_obj_t* container, int row) {
switch (param) {
case RADIO_POWER: //no break
case RADIO_FREQUENCY:
return new NumericParameterInput(handle, param, container, row);
case RADIO_BOOSTEDGAIN:
return new FlagParameterInput(handle, param, container, row);
default:
return nullptr;
}
}
static ParameterInput* makeParameterInput(RadioHandle handle, const RadioParameter param, const Modulation modulation, lv_obj_t* container, int row) {
auto base_input = makeBaseInput(handle, param, container, row);
if (base_input) return base_input;
switch (modulation) {
case MODULATION_LORA:
return makeLoraInput(handle, param, container, row);
case MODULATION_LRFHSS:
return makeLrFhssInput(handle, param, container, row);
default:
return new NumericParameterInput(handle, param, container, row);
}
}
void SettingsView::addPreset(Preset* preset) {
presets.pushBack(preset);
presetsByModulation[preset->modulation].pushBack(preset);
}
void SettingsView::queryRadios() {
DeviceId devices[MAX_RADIOS];
uint16_t device_count = 0;
if(!tt_hal_device_find(DEVICE_TYPE_RADIO, devices, &device_count, MAX_RADIOS)) {
// TT_LOG_W(TAG, "No radios registered with the system?");
} else {
for (size_t i = 0; (i < device_count) && (i < MAX_RADIOS); ++i) {
auto radio = tt_hal_radio_alloc(devices[i]);
if (radio) {
// TT_LOG_I(TAG, "Discovered radio \"%s\"", tt_hal_radio_get_name(radio));
radios.pushBack(radio);
} else {
// TT_LOG_E(TAG, "Error allocating radio handle for id=%d", devId);
}
}
}
}
void SettingsView::getRadioNames(Str &names, const char* const separator) {
int count = 1;
names.clear();
for (auto iter = radios.begin(); iter != radios.end(); iter++) {
Str name(tt_hal_radio_get_name(*iter));
auto last = is_last(iter, radios);
if (name == "") {
name.appendf("Unknown Radio %d", count);
}
names.append(name.c_str());
count++;
if (!last) {
names.append(separator);
}
}
}
int SettingsView::getModemAvailableIndex(Modulation m) {
for (size_t i = 0; i < modemsAvailableCount; ++i) {
if (modemsAvailable[i] == m) {
return i;
}
}
return -1;
}
lv_obj_t* SettingsView::initParameterFormGeneric(lv_obj_t *parent, const Modulation modem) {
lv_obj_t *container = propertiesForm;
if (container) {
lv_obj_clean(container);
lv_obj_del(container);
}
paramsAvailableCount = 0;
container = lv_obj_create(parent);
lv_obj_set_style_pad_all(container, 0, 0);
lv_obj_set_layout(container, LV_LAYOUT_GRID);
lv_obj_align(container, LV_ALIGN_TOP_MID, 0, 0);
const int grid_row_size = 40;
const int grid_col_size = 60;
static constexpr size_t row_dsc_last = RADIO_NARROWGRID + 1;
static lv_coord_t col_dsc[] = {LV_GRID_FR(1), LV_GRID_FR(1), grid_col_size, LV_GRID_TEMPLATE_LAST};
static lv_coord_t row_dsc[row_dsc_last] = {0};
for (size_t i = 0; i < row_dsc_last; ++i) {
row_dsc[i] = grid_row_size; //LV_GRID_FR(1);
}
row_dsc[row_dsc_last - 1] = LV_GRID_TEMPLATE_LAST;
lv_obj_set_grid_dsc_array(container, col_dsc, row_dsc);
char unit_buffer[32] = {0};
// Clean up any input
for (size_t i = 0; i < MAX_PARAMS; ++i) {
// As this is a LUT, only some may be set
if (paramInputs[i]) {
delete paramInputs[i];
paramInputs[i] = nullptr;
}
}
for (RadioParameter param = RADIO_POWER;
param <= RADIO_NARROWGRID;
param = static_cast<RadioParameter>((size_t)param + 1)) {
float value = 0.0;
Str value_buffer;
auto status = tt_hal_radio_get_parameter(radioSelected, param, &value);
if (status == RADIO_PARAM_SUCCESS) {
auto input = makeParameterInput(radioSelected, param, modem, container, paramsAvailableCount);
input->onUserChange([](void* ctx) {
SettingsView* self = (SettingsView*)ctx;
self->onParameterInput();
}, this);
paramInputs[param] = input;
//lv_group_focus_obj(input);
paramsAvailable[paramsAvailableCount] = param;
paramsAvailableCount++;
}
}
row_dsc[paramsAvailableCount] = LV_GRID_TEMPLATE_LAST;
lv_obj_set_grid_dsc_array(container, col_dsc, row_dsc);
lv_obj_set_size(container, lv_pct(100), lv_pct(100));
return container;
}
void SettingsView::selectModulation(int modemIndex) {
lv_dropdown_set_selected(modemDropdown, modemIndex);
if (tt_hal_radio_set_modulation(radioSelected, modemsAvailable[modemIndex])) {
propertiesForm = initParameterFormGeneric(mainPanel, modemsAvailable[modemIndex]);
}
updatePresets();
}
void SettingsView::selectPreset(int presetIndex) {
// The first index is always "No preset" or "None available"
// Other indices are the presets for the current modulation + 1
auto modem = tt_hal_radio_get_modulation(radioSelected);
auto& presets = presetsByModulation[modem];
if ((presetIndex > 0) && ((presetIndex - 1) < presets.size())) {
auto preset = presets[presetIndex - 1];
for (auto iter = preset->items.begin(); iter != preset->items.end(); iter++) {
if (paramInputs[iter->parameter]) {
paramInputs[iter->parameter]->setValue(iter->value);
paramInputs[iter->parameter]->storeToRadio();
}
}
} else {
crash("Selected preset does not exist");
}
}
void SettingsView::onParameterInput() {
// As the user did an input, this makes any applied
// preset inconsistent, revert back to "None".
lv_dropdown_set_selected(modemPresetDropdown, 0);
}
void SettingsView::updatePresets() {
auto modemIndexConfigured = tt_hal_radio_get_modulation(radioSelected);
Str preset_list("Select...");
auto& presets = presetsByModulation[modemIndexConfigured];
if (!presets.empty()) {
preset_list.append("\n");
}
for (auto iter = presets.begin(); iter != presets.end(); iter++) {
auto place_sep = !is_last(iter, presets);
auto& name = (*iter)->name;
preset_list.append(name.c_str());
if (place_sep) {
preset_list.append("\n");
}
}
if (preset_list.empty()) {
lv_obj_add_state(modemPresetDropdown, LV_STATE_DISABLED);
lv_dropdown_set_options(modemPresetDropdown, "None");
} else {
lv_obj_clear_state(modemPresetDropdown, LV_STATE_DISABLED);
lv_dropdown_set_options(modemPresetDropdown, preset_list.c_str());
}
}
void SettingsView::selectRadio(int index) {
if (radioStateSubId > -1) {
tt_hal_radio_unsubscribe_state(radioSelected, radioStateSubId);
}
radioSelected = radios[index];
for (size_t i = 0; i < MAX_MODEMS; ++i) {
modemsAvailable[i] = MODULATION_NONE;
}
Str modulation_list;
modemsAvailableCount = 1;
modemsAvailable[0] = MODULATION_NONE;
modulation_list.append(LV_SYMBOL_MINUS);
modulation_list.append(" ");
modulation_list.append(LV_SYMBOL_MINUS);
modulation_list.append(" ");
modulation_list.append("Disabled\n");
for (Modulation mod = FIRST_MODULATION;
mod <= LAST_MODULATION;
mod = static_cast<Modulation>((size_t)mod + 1)) {
bool canRx = tt_hal_radio_can_receive(radioSelected, mod);
bool canTx = tt_hal_radio_can_transmit(radioSelected, mod);
bool place_sep = (canRx || canTx) && (mod != LAST_MODULATION);
if (!canRx && !canTx) {
continue;
}
modemsAvailable[modemsAvailableCount] = mod;
modemsAvailableCount++;
if (canRx) {
modulation_list.append(LV_SYMBOL_DOWNLOAD);
modulation_list.append(" ");
} else {
modulation_list.append(LV_SYMBOL_MINUS);
modulation_list.append(" ");
}
if (canTx) {
modulation_list.append(LV_SYMBOL_UPLOAD);
modulation_list.append(" ");
} else {
modulation_list.append(LV_SYMBOL_MINUS);
modulation_list.append(" ");
}
modulation_list.append(toString(mod));
if (place_sep) {
modulation_list.append("\n");
}
}
lv_dropdown_set_options(modemDropdown, modulation_list.c_str());
auto modemIndexConfigured = getModemAvailableIndex(tt_hal_radio_get_modulation(radioSelected));
if (modemIndexConfigured > -1) {
lv_dropdown_set_selected(modemDropdown, modemIndexConfigured);
selectModulation(modemIndexConfigured);
}
updateSelectedRadioState(tt_hal_radio_get_state(radioSelected));
radioStateSubId = tt_hal_radio_subscribe_state(radioSelected, [](DeviceId id, RadioState state, void* ctx) {
SettingsView* self = (SettingsView*)ctx;
self->updateSelectedRadioState(state);
}, this);
}
lv_obj_t* SettingsView::initDeviceForm(lv_obj_t *parent) {
lv_obj_t *container = lv_obj_create(parent);
lv_obj_set_size(container, lv_pct(100), LV_SIZE_CONTENT);
lv_obj_set_style_pad_all(container, 0, 0);
const int grid_row_size = 40;
const int grid_col_size = 45;
static lv_coord_t lora_col_dsc[] = {LV_GRID_FR(1), LV_GRID_FR(1), grid_col_size, LV_GRID_TEMPLATE_LAST};
static lv_coord_t lora_row_dsc[] = {
grid_row_size,
grid_row_size,
grid_row_size,
grid_row_size,
LV_GRID_TEMPLATE_LAST};
lv_obj_set_layout(container, LV_LAYOUT_GRID);
lv_obj_set_grid_dsc_array(container, lora_col_dsc, lora_row_dsc);
Str radio_names;
getRadioNames(radio_names, "\n");
radioDropdown = createGridDropdownInput(container, 0, "Device", radio_names.c_str());
radioSwitch = lv_switch_create(container);
lv_obj_set_grid_cell(radioSwitch,
LV_GRID_ALIGN_STRETCH, 2, 1,
LV_GRID_ALIGN_CENTER, 0, 1);
lv_obj_set_size(radioSwitch, lv_pct(100), 20);
lv_obj_t* state_text = lv_label_create(container);
lv_label_set_text(state_text, "State");
lv_obj_set_grid_cell(state_text,
LV_GRID_ALIGN_STRETCH, 0, 1,
LV_GRID_ALIGN_CENTER, 1, 1);
lv_obj_set_size(state_text, lv_pct(100), LV_SIZE_CONTENT);
radioStateLabel = lv_label_create(container);
lv_label_set_text(radioStateLabel, "Unknown");
lv_obj_set_grid_cell(radioStateLabel,
LV_GRID_ALIGN_STRETCH, 1, 1,
LV_GRID_ALIGN_CENTER, 1, 1);
lv_obj_set_size(radioStateLabel, lv_pct(100), LV_SIZE_CONTENT);
modemDropdown = createGridDropdownInput(container, 2, "Modulation", "None available");
modemPresetDropdown = createGridDropdownInput(container, 3, "Preset", "None");
lv_obj_add_event_cb(modemDropdown, [](lv_event_t * e) {
SettingsView* self = (SettingsView*)lv_event_get_user_data(e);
lv_obj_t* input = lv_event_get_target_obj(e);
self->selectModulation(lv_dropdown_get_selected(input));
}, LV_EVENT_VALUE_CHANGED, this);
lv_obj_add_event_cb(modemPresetDropdown, [](lv_event_t * e) {
SettingsView* self = (SettingsView*)lv_event_get_user_data(e);
lv_obj_t* input = lv_event_get_target_obj(e);
self->selectPreset(lv_dropdown_get_selected(input));
}, LV_EVENT_VALUE_CHANGED, this);
lv_obj_add_event_cb(radioSwitch, [](lv_event_t * e) {
lv_obj_t* input = lv_event_get_target_obj(e);
SettingsView* self = (SettingsView*)lv_event_get_user_data(e);
self->enableSelectedRadio(lv_obj_has_state(input, LV_STATE_CHECKED));
}, LV_EVENT_VALUE_CHANGED, this);
selectRadio(0);
return container;
}
void SettingsView::updateSelectedRadioState(RadioState state) {
switch (state) {
case RADIO_PENDING_ON:
lv_label_set_text(radioStateLabel, "Activating...");
break;
case RADIO_ON:
lv_label_set_text(radioStateLabel, "Activated");
break;
case RADIO_ERROR:
lv_label_set_text(radioStateLabel, "Error");
break;
case RADIO_PENDING_OFF:
lv_label_set_text(radioStateLabel, "Deactivating...");
break;
case RADIO_OFF:
lv_label_set_text(radioStateLabel, "Deactivated");
break;
default:
lv_label_set_text(radioStateLabel, "Unknown");
break;
}
switch (state) {
case RADIO_OFF:
case RADIO_ERROR:
activateConfig();
break;
default:
deactivateConfig();
break;
}
}
bool SettingsView::enableSelectedRadio(bool enable) {
if (radioSelected) {
if (enable) {
return tt_hal_radio_start(radioSelected);
} else {
return tt_hal_radio_stop(radioSelected);
}
}
return false;
}
void SettingsView::activateConfig() {
lv_obj_clear_state(modemDropdown, LV_STATE_DISABLED);
lv_obj_clear_state(radioSwitch, LV_STATE_CHECKED);
lv_obj_clear_state(modemPresetDropdown, LV_STATE_DISABLED);
for (size_t i = 0; i < MAX_PARAMS; ++i) {
if (paramInputs[i]) {
paramInputs[i]->activate();
}
}
}
void SettingsView::deactivateConfig() {
lv_obj_add_state(radioSwitch, LV_STATE_CHECKED);
lv_obj_add_state(modemDropdown, LV_STATE_DISABLED);
lv_obj_add_state(modemPresetDropdown, LV_STATE_DISABLED);
for (size_t i = 0; i < MAX_PARAMS; ++i) {
if (paramInputs[i]) {
paramInputs[i]->deactivate();
}
}
}
void SettingsView::initUi(lv_obj_t *parent) {
mainPanel = lv_obj_create(parent);
lv_obj_set_size(mainPanel, lv_pct(100), lv_pct(100));
lv_obj_set_flex_flow(mainPanel, LV_FLEX_FLOW_COLUMN);
lv_obj_align(mainPanel, LV_ALIGN_TOP_MID, 0, 0);
lv_obj_set_style_border_width(mainPanel, 0, 0);
lv_obj_set_style_pad_all(mainPanel, 0, 0);
deviceForm = initDeviceForm(mainPanel);
}
void SettingsView::setVisible(bool visible) {
if (visible) {
lv_obj_clear_flag(mainPanel, LV_OBJ_FLAG_HIDDEN);
} else {
lv_obj_add_flag(mainPanel, LV_OBJ_FLAG_HIDDEN);
}
}

View File

@ -1,75 +0,0 @@
#pragma once
#include "Preset.h"
#include <tt_hal_radio.h>
#include <lvgl.h>
class ParameterInput;
class SettingsView {
static constexpr Modulation FIRST_MODULATION = MODULATION_NONE;
static constexpr Modulation LAST_MODULATION = MODULATION_LRFHSS;
static constexpr size_t MAX_RADIOS = 32;
static constexpr size_t MAX_MODEMS = LAST_MODULATION + 1;
static constexpr size_t MAX_PARAMS = RADIO_NARROWGRID + 1;
RadioHandle radioSelected = nullptr;
RadioStateSubscriptionId radioStateSubId = -1;
Modulation modemsAvailable[MAX_MODEMS] = {};
size_t modemsAvailableCount = 0;
RadioParameter paramsAvailable[MAX_PARAMS] = {};
ParameterInput* paramInputs[MAX_PARAMS] = {0};
size_t paramsAvailableCount = 0;
LinkedList<Preset*> presets;
LinkedList<Preset*> presetsByModulation[MAX_MODEMS];
lv_obj_t* mainPanel = nullptr;
lv_obj_t* deviceForm = nullptr;
lv_obj_t* radioDropdown = nullptr;
lv_obj_t* radioSwitch = nullptr;
lv_obj_t* radioStateLabel = nullptr;
lv_obj_t* modemDropdown = nullptr;
lv_obj_t* modemPresetDropdown = nullptr;
lv_obj_t* propertiesForm = nullptr;
public:
LinkedList<RadioHandle> radios;
void addPreset(Preset* preset);
void queryRadios();
void getRadioNames(Str &names, const char* const separator);
int getModemAvailableIndex(Modulation m);
lv_obj_t* initParameterFormGeneric(lv_obj_t *parent, const Modulation modem);
void selectModulation(int modemIndex);
void selectPreset(int presetIndex);
void onParameterInput();
void updatePresets();
void selectRadio(int index);
lv_obj_t *initDeviceForm(lv_obj_t *parent);
void updateSelectedRadioState(RadioState state);
bool enableSelectedRadio(bool enable);
void activateConfig();
void deactivateConfig();
void initUi(lv_obj_t *parent);
void setVisible(bool visible);
explicit SettingsView(lv_obj_t *parent) {
queryRadios();
initUi(parent);
}
};

View File

@ -1,106 +0,0 @@
#include "Utils.h"
#include <ctype.h>
#include <tt_app_alertdialog.h>
void crash(const char* const message) {
tt_app_alertdialog_start("RadioSet has crashed!", message, nullptr, 0);
}
void crashassert(bool assertion, const char* const message) {
if (!assertion) {
crash(message);
}
}
void hexdump(Str& out, const uint8_t* data, size_t size) {
out.clear();
for (size_t i = 0; i < size; ++i) {
out.appendf("%02X ", data[i]);
}
}
bool isPrintable(const uint8_t* data, size_t size) {
for (size_t i = 0; i < (size - 1); ++i) {
if (!isprint(data[i])) {
return false;
}
}
return true;
}
char *const toString(Modulation m) {
switch (m) {
case MODULATION_NONE:
return "None";
case MODULATION_LORA:
return "LoRa";
case MODULATION_FSK:
return "FSK";
case MODULATION_LRFHSS:
return "LR-FHSS";
default:
break;
}
crash("Unknown modulation passed.");
return "Unknown";
}
char *const toString(RadioParameter p) {
switch (p) {
case RADIO_POWER:
return "Power";
case RADIO_BOOSTEDGAIN:
return "RX Boosted Gain";
case RADIO_FREQUENCY:
return "Center Frequency";
case RADIO_BANDWIDTH:
return "Bandwidth";
case RADIO_SPREADFACTOR:
return "Spread Factor";
case RADIO_CODINGRATE:
return "Coding Rate";
case RADIO_SYNCWORD:
return "Sync Word";
case RADIO_PREAMBLES:
return "Preamble Length";
case RADIO_FREQDIV:
return "Frequency Deviation";
case RADIO_DATARATE:
return "Data Rate";
case RADIO_ADDRWIDTH:
return "Address Width";
case RADIO_NARROWGRID:
return "Narrow Grid";
default:
break;
}
crash("Unknown parameter passed.");
return "Unknown";
}
void clownvomit(lv_obj_t *obj) {
static auto rng = []() {
static int color = 0xCCC0FE;
const int a = 4711;
const int m = 0x10001;
color = (a * color) % m;
return color;
};
const int darken = 0x0E0E0E;
const int lighten = 0xFEFEFE;
lv_obj_set_style_bg_color(obj, lv_color_hex(rng() & darken), 0);
uint32_t i;
for(i = 0; i < lv_obj_get_child_count(obj); i++) {
auto light = lv_color_lighten(lv_color_hex(rng()), 100);
auto dark = lv_color_darken(lv_color_hex(rng()), 100);
lv_obj_t * child = lv_obj_get_child(obj, i);
lv_obj_set_style_bg_color(child, dark, 0);
lv_obj_set_style_border_color(child, light, 0);
lv_obj_set_style_border_width(child, 1, 0);
clownvomit(child);
}
}

View File

@ -1,29 +0,0 @@
#pragma once
#include "Str.h"
#include <lvgl.h>
#include <tt_hal_radio.h>
template <typename Iterator>
Iterator next(Iterator i) {
return i++;
}
template <typename Iterator, typename Container>
bool is_last(Iterator i, const Container& c) {
return (i != c.end()) && (next(i) == c.end());
}
void crash(const char* const message);
void crashassert(bool assertion, const char* const message);
void hexdump(Str& out, const uint8_t* data, size_t size);
bool isPrintable(const uint8_t* data, size_t size);
char *const toString(Modulation m);
char *const toString(RadioParameter p);
// Debug function which colors all children randomly
// TODO: Remove before flight
void clownvomit(lv_obj_t *obj);

View File

@ -70,8 +70,8 @@ struct RadioTxPacket {
};
typedef void (*RadioStateCallback)(DeviceId id, RadioState state, void* ctx);
typedef void (*RadioTxStateCallback)(RadioTxId id, RadioTxState state, void* ctx);
typedef void (*RadioOnReceiveCallback)(DeviceId id, const RadioRxPacket* packet, void* ctx);
typedef void (*RadioTxStateCallback)(RadioTxId id, RadioTxState state);
typedef void (*RadioOnReceiveCallback)(DeviceId id, const RadioRxPacket* packet);
/**
* Allocate a radio driver object for the specified radioId.
@ -194,19 +194,17 @@ bool tt_hal_radio_stop(RadioHandle handle);
* @param[in] handle the radio driver handle
* @param[in] packet packet to send (no special requirement for memory of data)
* @param[in] callback function to call on transmission state change for the packet
* @param[in] ctx context which will be passed to the callback function
* @return the identifier for the transmission
*/
RadioTxId tt_hal_radio_transmit(RadioHandle handle, RadioTxPacket packet, RadioTxStateCallback callback, void* ctx);
RadioTxId tt_hal_radio_transmit(RadioHandle handle, RadioTxPacket packet, RadioTxStateCallback callback);
/**
* Subscribe for any received packet that the radio driver object receives.
* @param[in] handle the radio driver handle
* @param[in] callback function to call on reception of a packet
* @param[in] ctx context which will be passed to the callback function
* @return the identifier for the subscription
*/
RadioRxSubscriptionId tt_hal_radio_subscribe_receive(RadioHandle handle, RadioOnReceiveCallback callback, void* ctx);
RadioRxSubscriptionId tt_hal_radio_subscribe_receive(RadioHandle handle, RadioOnReceiveCallback callback);
/**
* Subscribe for any state change of the radio driver object.

View File

@ -39,10 +39,7 @@ extern "C" {
RadioHandle tt_hal_radio_alloc(DeviceId radioId) {
auto radio = findValidRadioDevice(radioId);
if (radio != nullptr) {
return new DeviceWrapper(radio);
}
return nullptr;
return new DeviceWrapper(radio);
}
void tt_hal_radio_free(RadioHandle handle) {
@ -119,15 +116,15 @@ extern "C" {
return wrapper->device->stop();
}
RadioTxId tt_hal_radio_transmit(RadioHandle handle, RadioTxPacket packet, RadioTxStateCallback callback, void* ctx) {
RadioTxId tt_hal_radio_transmit(RadioHandle handle, RadioTxPacket packet, RadioTxStateCallback callback) {
auto wrapper = static_cast<DeviceWrapper*>(handle);
auto ttPacket = tt::hal::radio::TxPacket{
.data = std::vector<uint8_t>(packet.data, packet.data + packet.size),
.address = packet.address
};
return wrapper->device->transmit(ttPacket, [callback, ctx](tt::hal::radio::RadioDevice::TxId id, tt::hal::radio::RadioDevice::TransmissionState state) {
return wrapper->device->transmit(ttPacket, [callback](tt::hal::radio::RadioDevice::TxId id, tt::hal::radio::RadioDevice::TransmissionState state) {
if (callback) {
callback(id, fromCpp(state), ctx);
callback(id, fromCpp(state));
}
});
}
@ -141,9 +138,9 @@ extern "C" {
});
}
RadioRxSubscriptionId tt_hal_radio_subscribe_receive(RadioHandle handle, RadioOnReceiveCallback callback, void* ctx) {
RadioRxSubscriptionId tt_hal_radio_subscribe_receive(RadioHandle handle, RadioOnReceiveCallback callback) {
auto wrapper = static_cast<DeviceWrapper*>(handle);
return wrapper->device->subscribeRx([callback, ctx](tt::hal::Device::Id id, const tt::hal::radio::RxPacket& ttPacket) {
return wrapper->device->subscribeRx([callback](tt::hal::Device::Id id, const tt::hal::radio::RxPacket& ttPacket) {
if (callback) {
auto ttcPacket = RadioRxPacket{
.data = ttPacket.data.data(),
@ -151,7 +148,7 @@ extern "C" {
.rssi = ttPacket.rssi,
.snr = ttPacket.snr
};
callback(id, &ttcPacket, ctx);
callback(id, &ttcPacket);
}
});
}

View File

@ -62,8 +62,6 @@ const esp_elfsym elf_symbols[] {
ESP_ELFSYM_EXPORT(close),
// time.h
ESP_ELFSYM_EXPORT(clock_gettime),
ESP_ELFSYM_EXPORT(time),
ESP_ELFSYM_EXPORT(localtime),
ESP_ELFSYM_EXPORT(strftime),
// pthread
ESP_ELFSYM_EXPORT(pthread_create),
@ -389,9 +387,7 @@ const esp_elfsym elf_symbols[] {
ESP_ELFSYM_EXPORT(lv_event_get_current_target_obj),
// lv_color
ESP_ELFSYM_EXPORT(lv_color_black),
ESP_ELFSYM_EXPORT(lv_color_darken),
ESP_ELFSYM_EXPORT(lv_color_hex),
ESP_ELFSYM_EXPORT(lv_color_lighten),
ESP_ELFSYM_EXPORT(lv_color_make),
// lv_group
ESP_ELFSYM_EXPORT(lv_group_add_obj),
@ -417,8 +413,6 @@ const esp_elfsym elf_symbols[] {
ESP_ELFSYM_EXPORT(lv_obj_get_display),
ESP_ELFSYM_EXPORT(lv_obj_get_height),
ESP_ELFSYM_EXPORT(lv_obj_get_parent),
ESP_ELFSYM_EXPORT(lv_obj_get_scroll_x),
ESP_ELFSYM_EXPORT(lv_obj_get_scroll_y),
ESP_ELFSYM_EXPORT(lv_obj_get_style_grid_cell_column_pos),
ESP_ELFSYM_EXPORT(lv_obj_get_style_grid_cell_column_span),
ESP_ELFSYM_EXPORT(lv_obj_get_style_grid_cell_row_pos),
@ -437,8 +431,6 @@ const esp_elfsym elf_symbols[] {
ESP_ELFSYM_EXPORT(lv_obj_remove_event_cb),
ESP_ELFSYM_EXPORT(lv_obj_remove_flag),
ESP_ELFSYM_EXPORT(lv_obj_remove_state),
ESP_ELFSYM_EXPORT(lv_obj_scroll_to_x),
ESP_ELFSYM_EXPORT(lv_obj_scroll_to_y),
ESP_ELFSYM_EXPORT(lv_obj_set_align),
ESP_ELFSYM_EXPORT(lv_obj_set_flex_align),
ESP_ELFSYM_EXPORT(lv_obj_set_flex_flow),