Make all variables configurable.

pull/1090/head
Balazs Kelemen 2022-01-12 09:26:42 +01:00
rodzic f5004a66a1
commit 3fa00f603b
11 zmienionych plików z 165 dodań i 67 usunięć

Wyświetl plik

@ -79,6 +79,17 @@ typedef enum _PositionFlags {
PositionFlags_POS_TIMESTAMP = 256
} PositionFlags;
typedef enum _InputEventChar {
InputEventChar_NULL = 0,
InputEventChar_UP = 17,
InputEventChar_DOWN = 18,
InputEventChar_LEFT = 19,
InputEventChar_RIGHT = 20,
InputEventChar_SELECT = 10,
InputEventChar_BACK = 27,
InputEventChar_CANCEL = 24
} InputEventChar;
typedef enum _RadioConfig_UserPreferences_EnvironmentalMeasurementSensorType {
RadioConfig_UserPreferences_EnvironmentalMeasurementSensorType_DHT11 = 0,
RadioConfig_UserPreferences_EnvironmentalMeasurementSensorType_DS18B20 = 1
@ -157,6 +168,17 @@ typedef struct _RadioConfig_UserPreferences {
char mqtt_password[32];
bool is_lora_tx_disabled;
bool is_power_saving;
bool rotary1_enabled;
uint32_t rotary1_pin_a;
uint32_t rotary1_pin_b;
uint32_t rotary1_pin_press;
InputEventChar rotary1_event_cw;
InputEventChar rotary1_event_ccw;
InputEventChar rotary1_event_press;
bool canned_message_plugin_enabled;
char canned_message_plugin_allow_input_origin[16];
char canned_message_plugin_messages[1024];
bool canned_message_plugin_send_bell;
} RadioConfig_UserPreferences;
typedef struct _RadioConfig {
@ -190,6 +212,10 @@ typedef struct _RadioConfig {
#define _PositionFlags_MAX PositionFlags_POS_TIMESTAMP
#define _PositionFlags_ARRAYSIZE ((PositionFlags)(PositionFlags_POS_TIMESTAMP+1))
#define _InputEventChar_MIN InputEventChar_NULL
#define _InputEventChar_MAX InputEventChar_BACK
#define _InputEventChar_ARRAYSIZE ((InputEventChar)(InputEventChar_BACK+1))
#define _RadioConfig_UserPreferences_EnvironmentalMeasurementSensorType_MIN RadioConfig_UserPreferences_EnvironmentalMeasurementSensorType_DHT11
#define _RadioConfig_UserPreferences_EnvironmentalMeasurementSensorType_MAX RadioConfig_UserPreferences_EnvironmentalMeasurementSensorType_DS18B20
#define _RadioConfig_UserPreferences_EnvironmentalMeasurementSensorType_ARRAYSIZE ((RadioConfig_UserPreferences_EnvironmentalMeasurementSensorType)(RadioConfig_UserPreferences_EnvironmentalMeasurementSensorType_DS18B20+1))
@ -276,6 +302,17 @@ extern "C" {
#define RadioConfig_UserPreferences_mqtt_password_tag 156
#define RadioConfig_UserPreferences_is_lora_tx_disabled_tag 157
#define RadioConfig_UserPreferences_is_power_saving_tag 158
#define RadioConfig_UserPreferences_rotary1_enabled_tag 160
#define RadioConfig_UserPreferences_rotary1_pin_a_tag 161
#define RadioConfig_UserPreferences_rotary1_pin_b_tag 162
#define RadioConfig_UserPreferences_rotary1_pin_press_tag 163
#define RadioConfig_UserPreferences_rotary1_event_cw_tag 164
#define RadioConfig_UserPreferences_rotary1_event_ccw_tag 165
#define RadioConfig_UserPreferences_rotary1_event_press_tag 166
#define RadioConfig_UserPreferences_canned_message_plugin_enabled_tag 170
#define RadioConfig_UserPreferences_canned_message_plugin_allow_input_origin_tag 171
#define RadioConfig_UserPreferences_canned_message_plugin_messages_tag 172
#define RadioConfig_UserPreferences_canned_message_plugin_send_bell_tag 173
#define RadioConfig_preferences_tag 1
/* Struct field encoding specification for nanopb */
@ -356,6 +393,18 @@ X(a, STATIC, SINGULAR, STRING, mqtt_username, 155) \
X(a, STATIC, SINGULAR, STRING, mqtt_password, 156) \
X(a, STATIC, SINGULAR, BOOL, is_lora_tx_disabled, 157) \
X(a, STATIC, SINGULAR, BOOL, is_power_saving, 158)
X(a, STATIC, SINGULAR, STRING, mqtt_password, 156) \
X(a, STATIC, SINGULAR, BOOL, rotary1_enabled, 160) \
X(a, STATIC, SINGULAR, UINT32, rotary1_pin_a, 161) \
X(a, STATIC, SINGULAR, UINT32, rotary1_pin_b, 162) \
X(a, STATIC, SINGULAR, UINT32, rotary1_pin_press, 163) \
X(a, STATIC, SINGULAR, UENUM, rotary1_event_cw, 164) \
X(a, STATIC, SINGULAR, UENUM, rotary1_event_ccw, 165) \
X(a, STATIC, SINGULAR, UENUM, rotary1_event_press, 166) \
X(a, STATIC, SINGULAR, BOOL, canned_message_plugin_enabled, 170) \
X(a, STATIC, SINGULAR, STRING, canned_message_plugin_allow_input_origin, 171) \
X(a, STATIC, SINGULAR, STRING, canned_message_plugin_messages, 172) \
X(a, STATIC, SINGULAR, BOOL, canned_message_plugin_send_bell, 173)
#define RadioConfig_UserPreferences_CALLBACK NULL
#define RadioConfig_UserPreferences_DEFAULT NULL

Wyświetl plik

@ -1,7 +1,6 @@
#include "configuration.h"
#include "CannedMessagePlugin.h"
#include "MeshService.h"
#include "input/InputBroker.h"
#include <assert.h>
@ -11,32 +10,89 @@ CannedMessagePlugin::CannedMessagePlugin()
: SinglePortPlugin("canned", PortNum_TEXT_MESSAGE_APP),
concurrency::OSThread("CannedMessagePlugin")
{
if (true) // if module enabled
if (radioConfig.preferences.canned_message_plugin_enabled)
{
if(this->splitConfiguredMessages() <= 0)
{
radioConfig.preferences.canned_message_plugin_enabled = false;
DEBUG_MSG("CannedMessagePlugin: No messages are configured. Plugin is disabled\n");
return;
}
this->inputObserver.observe(inputBroker);
}
}
/**
* @brief Items in array this->messages will be set to be pointing on the right
* starting points of the string radioConfig.preferences.canned_message_plugin_messages
*
* @return int Returns the number of messages found.
*/
int CannedMessagePlugin::splitConfiguredMessages()
{
int messageIndex = 0;
int i = 0;
this->messages[messageIndex++] = radioConfig.preferences.canned_message_plugin_messages;
int upTo = strlen(radioConfig.preferences.canned_message_plugin_messages) - 1;
while (i < upTo)
{
if (radioConfig.preferences.canned_message_plugin_messages[i] == '|')
{
// Message ending found, replace it with string-end character.
radioConfig.preferences.canned_message_plugin_messages[i] = '\0';
DEBUG_MSG("CannedMessage %d is: '%s'\n", messageIndex-1, this->messages[messageIndex-1]);
if (messageIndex >= CANNED_MESSAGE_PLUGIN_MESSAGE_MAX_COUNT)
{
this->messagesCount = messageIndex;
return this->messagesCount;
}
// Next message starts after pipe (|) just found.
this->messages[messageIndex++] =
(radioConfig.preferences.canned_message_plugin_messages + i + 1);
}
i += 1;
}
if (strlen(this->messages[messageIndex-1]) > 0)
{
DEBUG_MSG("CannedMessage %d is: '%s'\n", messageIndex-1, this->messages[messageIndex-1]);
this->messagesCount = messageIndex;
}
else
{
this->messagesCount = messageIndex-1;
}
return this->messagesCount;
}
int CannedMessagePlugin::handleInputEvent(const InputEvent *event)
{
if (false) // test event->origin
if (
(strlen(radioConfig.preferences.canned_message_plugin_allow_input_origin) > 0) &&
(strcmp(radioConfig.preferences.canned_message_plugin_allow_input_origin, event->origin) != 0) &&
(strcmp(radioConfig.preferences.canned_message_plugin_allow_input_origin, "_any") != 0))
{
// Event origin is not accepted.
return 0;
}
bool validEvent = false;
if (event->inputEvent == INPUT_EVENT_UP)
if (event->inputEvent == static_cast<char>(InputEventChar_UP))
{
DEBUG_MSG("Canned message event UP\n");
this->action = CANNED_MESSAGE_ACTION_UP;
validEvent = true;
}
if (event->inputEvent == INPUT_EVENT_DOWN)
if (event->inputEvent == static_cast<char>(InputEventChar_DOWN))
{
DEBUG_MSG("Canned message event DOWN\n");
this->action = CANNED_MESSAGE_ACTION_DOWN;
validEvent = true;
}
if (event->inputEvent == INPUT_EVENT_SELECT)
if (event->inputEvent == static_cast<char>(InputEventChar_SELECT))
{
DEBUG_MSG("Canned message event Select\n");
this->action = CANNED_MESSAGE_ACTION_SELECT;
@ -61,6 +117,13 @@ void CannedMessagePlugin::sendText(NodeNum dest,
p->to = dest;
p->decoded.payload.size = strlen(message);
memcpy(p->decoded.payload.bytes, message, p->decoded.payload.size);
if (radioConfig.preferences.canned_message_plugin_send_bell)
{
p->decoded.payload.bytes[p->decoded.payload.size-1] = 7; // Bell character
p->decoded.payload.bytes[p->decoded.payload.size] = '\0'; // Bell character
p->decoded.payload.size++;
}
// PacketId prevPacketId = p->id; // In case we need it later.
@ -72,6 +135,10 @@ void CannedMessagePlugin::sendText(NodeNum dest,
int32_t CannedMessagePlugin::runOnce()
{
if (!radioConfig.preferences.canned_message_plugin_enabled)
{
return 30000; // TODO: should return MAX_VAL
}
DEBUG_MSG("Check status\n");
if (this->sendingState == SENDING_STATE_ACTIVE)
{
@ -89,7 +156,7 @@ int32_t CannedMessagePlugin::runOnce()
{
sendText(
NODENUM_BROADCAST,
cannedMessagePluginMessages[this->currentMessageIndex],
this->messages[this->currentMessageIndex],
true);
this->sendingState = SENDING_STATE_ACTIVE;
this->currentMessageIndex = -1;
@ -98,14 +165,12 @@ int32_t CannedMessagePlugin::runOnce()
else if (this->action == CANNED_MESSAGE_ACTION_UP)
{
this->currentMessageIndex = getPrevIndex();
DEBUG_MSG("MOVE UP. Current message:%ld\n",
millis());
DEBUG_MSG("MOVE UP");
}
else if (this->action == CANNED_MESSAGE_ACTION_DOWN)
{
this->currentMessageIndex = this->getNextIndex();
DEBUG_MSG("MOVE DOWN. Current message:%ld\n",
millis());
DEBUG_MSG("MOVE DOWN");
}
if (this->action != CANNED_MESSAGE_ACTION_NONE)
{
@ -113,20 +178,20 @@ int32_t CannedMessagePlugin::runOnce()
this->notifyObservers(NULL);
}
return 30000;
return 30000; // TODO: should return MAX_VAL
}
String CannedMessagePlugin::getCurrentMessage()
{
return cannedMessagePluginMessages[this->currentMessageIndex];
return this->messages[this->currentMessageIndex];
}
String CannedMessagePlugin::getPrevMessage()
{
return cannedMessagePluginMessages[this->getPrevIndex()];
return this->messages[this->getPrevIndex()];
}
String CannedMessagePlugin::getNextMessage()
{
return cannedMessagePluginMessages[this->getNextIndex()];
return this->messages[this->getNextIndex()];
}
bool CannedMessagePlugin::shouldDraw()
{
@ -139,8 +204,7 @@ cannedMessagePluginSendigState CannedMessagePlugin::getSendingState()
int CannedMessagePlugin::getNextIndex()
{
if (this->currentMessageIndex >=
(sizeof(cannedMessagePluginMessages) / CANNED_MESSAGE_PLUGIN_MESSAGE_MAX_LEN) - 1)
if (this->currentMessageIndex >= (this->messagesCount -1))
{
return 0;
}
@ -154,8 +218,7 @@ int CannedMessagePlugin::getPrevIndex()
{
if (this->currentMessageIndex <= 0)
{
return
sizeof(cannedMessagePluginMessages) / CANNED_MESSAGE_PLUGIN_MESSAGE_MAX_LEN - 1;
return this->messagesCount - 1;
}
else
{

Wyświetl plik

@ -1,6 +1,6 @@
#pragma once
#include "SinglePortPlugin.h"
#include "input/HardwareInput.h"
#include "input/InputBroker.h"
enum cannedMessagePluginActionType
{
@ -16,20 +16,7 @@ enum cannedMessagePluginSendigState
SENDING_STATE_ACTIVE
};
#define CANNED_MESSAGE_PLUGIN_MESSAGE_MAX_LEN 50
static char cannedMessagePluginMessages[][CANNED_MESSAGE_PLUGIN_MESSAGE_MAX_LEN] =
{
"Need helping hand",
"Help me with saw",
"I need an alpinist",
"I need ambulance",
"I'm fine",
"I'm already waiting",
"I will be late",
"I couldn't join",
"We have company"
};
#define CANNED_MESSAGE_PLUGIN_MESSAGE_MAX_COUNT 50
class CannedMessagePlugin :
public SinglePortPlugin,
@ -59,6 +46,7 @@ class CannedMessagePlugin :
const char* message,
bool wantReplies);
int splitConfiguredMessages();
int getNextIndex();
int getPrevIndex();
@ -67,6 +55,9 @@ class CannedMessagePlugin :
volatile cannedMessagePluginActionType action = CANNED_MESSAGE_ACTION_NONE;
int currentMessageIndex = -1;
cannedMessagePluginSendigState sendingState = SENDING_STATE_NONE;
char *messages[CANNED_MESSAGE_PLUGIN_MESSAGE_MAX_COUNT];
int messagesCount = 0;
};
extern CannedMessagePlugin *cannedMessagePlugin;

Wyświetl plik

@ -36,9 +36,7 @@ void setupPlugins()
new ReplyPlugin();
rotaryEncoderInterruptImpl1 =
new RotaryEncoderInterruptImpl1();
rotaryEncoderInterruptImpl1->init(
22, 23, 21,
INPUT_EVENT_UP, INPUT_EVENT_DOWN, INPUT_EVENT_SELECT);
rotaryEncoderInterruptImpl1->init();
cannedMessagePlugin = new CannedMessagePlugin();
#ifndef NO_ESP32

Wyświetl plik

@ -1,15 +0,0 @@
#pragma once
#define INPUT_EVENT_NULL 0
#define INPUT_EVENT_UP 17
#define INPUT_EVENT_DOWN 18
#define INPUT_EVENT_LEFT 19
#define INPUT_EVENT_RIGHT 20
#define INPUT_EVENT_SELECT '\n'
#define INPUT_EVENT_BACK 27
#define INPUT_EVENT_CANCEL 24
typedef struct _InputEvent {
const char* origin;
char inputEvent;
} InputEvent;

Wyświetl plik

@ -14,4 +14,5 @@ void InputBroker::registerOrigin(Observable<const InputEvent *> *origin)
int InputBroker::handleInputEvent(const InputEvent *event)
{
this->notifyObservers(event);
return 0;
}

Wyświetl plik

@ -1,7 +1,10 @@
#pragma once
#include "Observer.h"
#include "HardwareInput.h"
typedef struct _InputEvent {
const char* origin;
char inputEvent;
} InputEvent;
class InputBroker :
public Observable<const InputEvent *>
{

Wyświetl plik

@ -1,11 +1,6 @@
#include "configuration.h"
#include "RotaryEncoderInterruptBase.h"
/*#define PIN_PUSH 21
#define PIN_A 22
#define PIN_B 23
*/
RotaryEncoderInterruptBase::RotaryEncoderInterruptBase(
const char *name) :
concurrency::OSThread(name)
@ -44,7 +39,7 @@ void RotaryEncoderInterruptBase::init(
int32_t RotaryEncoderInterruptBase::runOnce()
{
InputEvent e;
e.inputEvent = INPUT_EVENT_NULL;
e.inputEvent = InputEventChar_NULL;
e.origin = this->_originName;
if (this->action == ROTARY_ACTION_PRESSED)
@ -63,7 +58,7 @@ int32_t RotaryEncoderInterruptBase::runOnce()
e.inputEvent = this->_eventCcw;
}
if (e.inputEvent != INPUT_EVENT_NULL)
if (e.inputEvent != InputEventChar_NULL)
{
this->notifyObservers(&e);
}

Wyświetl plik

@ -1,7 +1,7 @@
#pragma once
#include "SinglePortPlugin.h" // TODO: what header file to include?
#include "HardwareInput.h"
#include "InputBroker.h"
enum RotaryEncoderInterruptBaseStateType
{

Wyświetl plik

@ -9,10 +9,25 @@ RotaryEncoderInterruptImpl1::RotaryEncoderInterruptImpl1() :
{
}
void RotaryEncoderInterruptImpl1::init(
uint8_t pinA, uint8_t pinB, uint8_t pinPress,
char eventCw, char eventCcw, char eventPressed)
void RotaryEncoderInterruptImpl1::init()
{
if (!radioConfig.preferences.rotary1_enabled)
{
// Input device is disabled.
return;
}
uint8_t pinA = radioConfig.preferences.rotary1_pin_a;
uint8_t pinB = radioConfig.preferences.rotary1_pin_b;
uint8_t pinPress = radioConfig.preferences.rotary1_pin_press;
char eventCw =
static_cast<char>(radioConfig.preferences.rotary1_event_cw);
char eventCcw =
static_cast<char>(radioConfig.preferences.rotary1_event_ccw);
char eventPressed =
static_cast<char>(radioConfig.preferences.rotary1_event_press);
//radioConfig.preferences.ext_notification_plugin_output
RotaryEncoderInterruptBase::init(
pinA, pinB, pinPress,
eventCw, eventCcw, eventPressed,

Wyświetl plik

@ -13,9 +13,7 @@ class RotaryEncoderInterruptImpl1 :
{
public:
RotaryEncoderInterruptImpl1();
void init(
uint8_t pinA, uint8_t pinB, uint8_t pinPress,
char eventCw, char eventCcw, char eventPressed);
void init();
static void handleIntA();
static void handleIntB();
static void handleIntPressed();