Merge pull request #163 from bobbycar-graz/more_tasks_in_taskmanager
More more tasks into task manager
This commit is contained in:
@ -49,6 +49,7 @@ set(headers
|
|||||||
cloudtexthelpers.h
|
cloudtexthelpers.h
|
||||||
controller.h
|
controller.h
|
||||||
debugcolorhelpers.h
|
debugcolorhelpers.h
|
||||||
|
debuginputhandler.h
|
||||||
debugtexthelpers.h
|
debugtexthelpers.h
|
||||||
displays/bmsdisplay.h
|
displays/bmsdisplay.h
|
||||||
displays/calibratedisplay.h
|
displays/calibratedisplay.h
|
||||||
@ -185,8 +186,7 @@ set(headers
|
|||||||
qrimport.h
|
qrimport.h
|
||||||
rotary.h
|
rotary.h
|
||||||
screens.h
|
screens.h
|
||||||
serial.h
|
serial_bobby.h
|
||||||
serialhandler.h
|
|
||||||
settings.h
|
settings.h
|
||||||
settingspersister.h
|
settingspersister.h
|
||||||
settingsutils.h
|
settingsutils.h
|
||||||
@ -264,6 +264,7 @@ set(sources
|
|||||||
cloudtexthelpers.cpp
|
cloudtexthelpers.cpp
|
||||||
controller.cpp
|
controller.cpp
|
||||||
debugcolorhelpers.cpp
|
debugcolorhelpers.cpp
|
||||||
|
debuginputhandler.cpp
|
||||||
debugtexthelpers.cpp
|
debugtexthelpers.cpp
|
||||||
displays/bmsdisplay.cpp
|
displays/bmsdisplay.cpp
|
||||||
displays/calibratedisplay.cpp
|
displays/calibratedisplay.cpp
|
||||||
@ -401,8 +402,7 @@ set(sources
|
|||||||
qrimport.cpp
|
qrimport.cpp
|
||||||
rotary.cpp
|
rotary.cpp
|
||||||
screens.cpp
|
screens.cpp
|
||||||
serial.cpp
|
serial_bobby.cpp
|
||||||
serialhandler.cpp
|
|
||||||
settings.cpp
|
settings.cpp
|
||||||
settingspersister.cpp
|
settingspersister.cpp
|
||||||
settingsutils.cpp
|
settingsutils.cpp
|
||||||
|
@ -130,11 +130,6 @@ struct StatsUpdateRateAccessor : public RefAccessorSaveSettings<int16_t> { int16
|
|||||||
struct DisplayUpdateRateAccessor : public RefAccessorSaveSettings<int16_t> { int16_t &getRef() const override { return settings.boardcomputerHardware.timersSettings.displayUpdateRate; } };
|
struct DisplayUpdateRateAccessor : public RefAccessorSaveSettings<int16_t> { int16_t &getRef() const override { return settings.boardcomputerHardware.timersSettings.displayUpdateRate; } };
|
||||||
struct DisplayRedrawRateAccessor : public RefAccessorSaveSettings<int16_t> { int16_t &getRef() const override { return settings.boardcomputerHardware.timersSettings.displayRedrawRate; } };
|
struct DisplayRedrawRateAccessor : public RefAccessorSaveSettings<int16_t> { int16_t &getRef() const override { return settings.boardcomputerHardware.timersSettings.displayRedrawRate; } };
|
||||||
|
|
||||||
// CAN
|
|
||||||
#ifdef FEATURE_CAN
|
|
||||||
struct CanReceiveRateAccessor : public RefAccessorSaveSettings<int16_t> { int16_t &getRef() const override { return settings.boardcomputerHardware.timersSettings.canReceiveRate; } };
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Cloud
|
// Cloud
|
||||||
#ifdef FEATURE_CLOUD
|
#ifdef FEATURE_CLOUD
|
||||||
struct CloudCollectRateAccessor : public RefAccessorSaveSettings<int16_t> { int16_t &getRef() const override { return settings.boardcomputerHardware.timersSettings.cloudCollectRate; } };
|
struct CloudCollectRateAccessor : public RefAccessorSaveSettings<int16_t> { int16_t &getRef() const override { return settings.boardcomputerHardware.timersSettings.cloudCollectRate; } };
|
||||||
|
127
main/debuginputhandler.cpp
Normal file
127
main/debuginputhandler.cpp
Normal file
@ -0,0 +1,127 @@
|
|||||||
|
#include "debuginputhandler.h"
|
||||||
|
|
||||||
|
// Arduino includes
|
||||||
|
#include <HardwareSerial.h>
|
||||||
|
|
||||||
|
// 3rdparty lib includes
|
||||||
|
#include <tftinstance.h>
|
||||||
|
|
||||||
|
// local includes
|
||||||
|
#include "globals.h"
|
||||||
|
#include "utils.h"
|
||||||
|
#include "screens.h"
|
||||||
|
#include "buttons.h"
|
||||||
|
|
||||||
|
using namespace espgui;
|
||||||
|
|
||||||
|
//wl_status_t last_status;
|
||||||
|
//IPAddress last_ip;
|
||||||
|
|
||||||
|
void initDebugInput()
|
||||||
|
{
|
||||||
|
Serial.begin(115200);
|
||||||
|
//Serial.setDebugOutput(true);
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleDebugInput()
|
||||||
|
{
|
||||||
|
//const auto status = WiFi.status();
|
||||||
|
//if (last_status != status)
|
||||||
|
//{
|
||||||
|
//Serial.print("Status changed to: ");
|
||||||
|
//Serial.println(to_string(status).c_str());
|
||||||
|
//last_status = status;
|
||||||
|
//}
|
||||||
|
|
||||||
|
//const auto ip = WiFi.localIP();
|
||||||
|
//if (last_ip != ip)
|
||||||
|
//{
|
||||||
|
//Serial.print("IP changed to: ");
|
||||||
|
//Serial.println(to_string(ip).c_str());
|
||||||
|
//last_ip = ip;
|
||||||
|
//}
|
||||||
|
|
||||||
|
while(Serial.available())
|
||||||
|
{
|
||||||
|
const auto c = Serial.read();
|
||||||
|
|
||||||
|
switch (c)
|
||||||
|
{
|
||||||
|
case 'i':
|
||||||
|
case 'I':
|
||||||
|
tft.init();
|
||||||
|
break;
|
||||||
|
case 'p':
|
||||||
|
case 'P':
|
||||||
|
{
|
||||||
|
const auto firstPower = controllers.front.command.poweroff;
|
||||||
|
for (Controller &controller : controllers)
|
||||||
|
controller.command.poweroff = !firstPower;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 'l':
|
||||||
|
case 'L':
|
||||||
|
{
|
||||||
|
const auto firstLed = controllers.front.command.led;
|
||||||
|
for (Controller &controller : controllers)
|
||||||
|
controller.command.led = !firstLed;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 'r':
|
||||||
|
case 'R':
|
||||||
|
loadSettings();
|
||||||
|
break;
|
||||||
|
case 's':
|
||||||
|
case 'S':
|
||||||
|
saveSettings();
|
||||||
|
break;
|
||||||
|
case '0':
|
||||||
|
case '1':
|
||||||
|
case '2':
|
||||||
|
case '3':
|
||||||
|
case '4':
|
||||||
|
case '5':
|
||||||
|
case '6':
|
||||||
|
case '7':
|
||||||
|
case '8':
|
||||||
|
case '9':
|
||||||
|
for (Controller &controller : controllers)
|
||||||
|
controller.command.buzzer.freq = c-'0';
|
||||||
|
break;
|
||||||
|
case 'A':
|
||||||
|
InputDispatcher::rotate(-1);
|
||||||
|
break;
|
||||||
|
case 'B':
|
||||||
|
InputDispatcher::rotate(1);
|
||||||
|
break;
|
||||||
|
case 'C':
|
||||||
|
InputDispatcher::confirmButton(true);
|
||||||
|
InputDispatcher::confirmButton(false);
|
||||||
|
break;
|
||||||
|
case 'D':
|
||||||
|
InputDispatcher::backButton(true);
|
||||||
|
InputDispatcher::backButton(false);
|
||||||
|
break;
|
||||||
|
case 'z':
|
||||||
|
case 'Z':
|
||||||
|
#ifndef LEDSTRIP_WRONG_DIRECTION
|
||||||
|
InputDispatcher::blinkLeftButton(true);
|
||||||
|
InputDispatcher::blinkLeftButton(false);
|
||||||
|
#else
|
||||||
|
InputDispatcher::blinkRightButton(true);
|
||||||
|
InputDispatcher::blinkRightButton(false);
|
||||||
|
#endif
|
||||||
|
break;
|
||||||
|
case 'u':
|
||||||
|
case 'U':
|
||||||
|
#ifndef LEDSTRIP_WRONG_DIRECTION
|
||||||
|
InputDispatcher::blinkRightButton(true);
|
||||||
|
InputDispatcher::blinkRightButton(false);
|
||||||
|
#else
|
||||||
|
InputDispatcher::blinkLeftButton(true);
|
||||||
|
InputDispatcher::blinkLeftButton(false);
|
||||||
|
#endif
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
@ -3,4 +3,5 @@
|
|||||||
//extern wl_status_t last_status;
|
//extern wl_status_t last_status;
|
||||||
//extern IPAddress last_ip;
|
//extern IPAddress last_ip;
|
||||||
|
|
||||||
void handleSerial();
|
void initDebugInput();
|
||||||
|
void handleDebugInput();
|
@ -42,16 +42,6 @@ using DisplayRedrawRateChangeDisplay = makeComponent<
|
|||||||
BackActionInterface<SwitchScreenAction<TimersMenu>>,
|
BackActionInterface<SwitchScreenAction<TimersMenu>>,
|
||||||
SwitchScreenAction<TimersMenu>
|
SwitchScreenAction<TimersMenu>
|
||||||
>;
|
>;
|
||||||
|
|
||||||
#ifdef FEATURE_CAN
|
|
||||||
using CanReceiveRateChangeDisplay = makeComponent<
|
|
||||||
ChangeValueDisplay<int16_t>,
|
|
||||||
StaticText<TEXT_CANRECEIVERATE>,
|
|
||||||
CanReceiveRateAccessor,
|
|
||||||
BackActionInterface<SwitchScreenAction<TimersMenu>>,
|
|
||||||
SwitchScreenAction<TimersMenu>
|
|
||||||
>;
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
TimersMenu::TimersMenu()
|
TimersMenu::TimersMenu()
|
||||||
@ -60,9 +50,6 @@ TimersMenu::TimersMenu()
|
|||||||
constructMenuItem<makeComponent<MenuItem, StaticText<TEXT_STATSUPDATERATE>, SwitchScreenAction<StatsUpdateRateChangeDisplay>>>();
|
constructMenuItem<makeComponent<MenuItem, StaticText<TEXT_STATSUPDATERATE>, SwitchScreenAction<StatsUpdateRateChangeDisplay>>>();
|
||||||
constructMenuItem<makeComponent<MenuItem, StaticText<TEXT_DISPLAYUPDATERATE>, SwitchScreenAction<DisplayUpdateRateChangeDisplay>>>();
|
constructMenuItem<makeComponent<MenuItem, StaticText<TEXT_DISPLAYUPDATERATE>, SwitchScreenAction<DisplayUpdateRateChangeDisplay>>>();
|
||||||
constructMenuItem<makeComponent<MenuItem, StaticText<TEXT_DISPLAYREDRAWRATE>, SwitchScreenAction<DisplayRedrawRateChangeDisplay>>>();
|
constructMenuItem<makeComponent<MenuItem, StaticText<TEXT_DISPLAYREDRAWRATE>, SwitchScreenAction<DisplayRedrawRateChangeDisplay>>>();
|
||||||
#ifdef FEATURE_CAN
|
|
||||||
constructMenuItem<makeComponent<MenuItem, StaticText<TEXT_CANRECEIVERATE>, SwitchScreenAction<CanReceiveRateChangeDisplay>>>();
|
|
||||||
#endif
|
|
||||||
constructMenuItem<makeComponent<MenuItem, StaticText<TEXT_BACK>, SwitchScreenAction<BoardcomputerHardwareSettingsMenu>, StaticMenuItemIcon<&espgui::icons::back>>>();
|
constructMenuItem<makeComponent<MenuItem, StaticText<TEXT_BACK>, SwitchScreenAction<BoardcomputerHardwareSettingsMenu>, StaticMenuItemIcon<&espgui::icons::back>>>();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -25,22 +25,8 @@ using namespace std::chrono_literals;
|
|||||||
#include "macros_bobbycar.h"
|
#include "macros_bobbycar.h"
|
||||||
#include "globals.h"
|
#include "globals.h"
|
||||||
#include "screens.h"
|
#include "screens.h"
|
||||||
#include "serialhandler.h"
|
|
||||||
#ifdef FEATURE_OTA
|
|
||||||
#include "ota.h"
|
|
||||||
#include "displays/menus/selectbuildservermenu.h"
|
|
||||||
#endif
|
|
||||||
#include "presets.h"
|
#include "presets.h"
|
||||||
#include "statistics.h"
|
#include "statistics.h"
|
||||||
#ifdef FEATURE_BLE
|
|
||||||
#include "ble_bobby.h"
|
|
||||||
#endif
|
|
||||||
#ifdef FEATURE_WEBSERVER
|
|
||||||
#include "webserver.h"
|
|
||||||
#endif
|
|
||||||
#ifdef FEATURE_CAN
|
|
||||||
#include "can.h"
|
|
||||||
#endif
|
|
||||||
#ifdef FEATURE_CLOUD
|
#ifdef FEATURE_CLOUD
|
||||||
#include "cloud.h"
|
#include "cloud.h"
|
||||||
#include "udpcloud.h"
|
#include "udpcloud.h"
|
||||||
@ -68,12 +54,6 @@ std::optional<espchrono::millis_clock::time_point> lastModeUpdate;
|
|||||||
std::optional<espchrono::millis_clock::time_point> lastStatsUpdate;
|
std::optional<espchrono::millis_clock::time_point> lastStatsUpdate;
|
||||||
std::optional<espchrono::millis_clock::time_point> lastDisplayUpdate;
|
std::optional<espchrono::millis_clock::time_point> lastDisplayUpdate;
|
||||||
std::optional<espchrono::millis_clock::time_point> lastDisplayRedraw;
|
std::optional<espchrono::millis_clock::time_point> lastDisplayRedraw;
|
||||||
#ifdef FEATURE_CAN
|
|
||||||
std::optional<espchrono::millis_clock::time_point> lastCanParse;
|
|
||||||
#endif
|
|
||||||
#ifdef FEATURE_BLE
|
|
||||||
std::optional<espchrono::millis_clock::time_point> lastBleUpdate;
|
|
||||||
#endif
|
|
||||||
#ifdef FEATURE_CLOUD
|
#ifdef FEATURE_CLOUD
|
||||||
std::optional<espchrono::millis_clock::time_point> lastCloudCollect;
|
std::optional<espchrono::millis_clock::time_point> lastCloudCollect;
|
||||||
std::optional<espchrono::millis_clock::time_point> lastCloudSend;
|
std::optional<espchrono::millis_clock::time_point> lastCloudSend;
|
||||||
@ -85,10 +65,6 @@ std::optional<espchrono::millis_clock::time_point> lastLedstripUpdate;
|
|||||||
|
|
||||||
extern "C" void app_main()
|
extern "C" void app_main()
|
||||||
{
|
{
|
||||||
Serial.begin(115200);
|
|
||||||
//Serial.setDebugOutput(true);
|
|
||||||
//Serial.println("setup()");
|
|
||||||
|
|
||||||
#ifdef FEATURE_LEDBACKLIGHT
|
#ifdef FEATURE_LEDBACKLIGHT
|
||||||
pinMode(PINS_LEDBACKLIGHT, OUTPUT);
|
pinMode(PINS_LEDBACKLIGHT, OUTPUT);
|
||||||
digitalWrite(PINS_LEDBACKLIGHT, ledBacklightInverted ? LOW : HIGH);
|
digitalWrite(PINS_LEDBACKLIGHT, ledBacklightInverted ? LOW : HIGH);
|
||||||
@ -133,22 +109,6 @@ extern "C" void app_main()
|
|||||||
task.setup();
|
task.setup();
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef FEATURE_CAN
|
|
||||||
bootLabel.redraw("can");
|
|
||||||
can::initCan();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef FEATURE_SERIAL
|
|
||||||
bootLabel.redraw("front Serial begin");
|
|
||||||
controllers.front.serial.get().begin(38400, SERIAL_8N1, PINS_RX1, PINS_TX1);
|
|
||||||
|
|
||||||
bootLabel.redraw("back Serial begin");
|
|
||||||
controllers.back.serial.get().begin(38400, SERIAL_8N1, PINS_RX2, PINS_TX2);
|
|
||||||
|
|
||||||
bootLabel.redraw("swap front back");
|
|
||||||
updateSwapFrontBack();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef FEATURE_LEDSTRIP
|
#ifdef FEATURE_LEDSTRIP
|
||||||
bootLabel.redraw("LED strip");
|
bootLabel.redraw("LED strip");
|
||||||
initLedStrip();
|
initLedStrip();
|
||||||
@ -159,24 +119,6 @@ extern "C" void app_main()
|
|||||||
|
|
||||||
currentMode = &modes::defaultMode;
|
currentMode = &modes::defaultMode;
|
||||||
|
|
||||||
#ifdef FEATURE_OTA
|
|
||||||
bootLabel.redraw("ota");
|
|
||||||
initOta();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef FEATURE_BLE
|
|
||||||
bootLabel.redraw("ble");
|
|
||||||
initBle();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef FEATURE_WEBSERVER
|
|
||||||
bootLabel.redraw("webserver");
|
|
||||||
initWebserver();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
bootLabel.redraw("potis");
|
|
||||||
readPotis();
|
|
||||||
|
|
||||||
#ifdef FEATURE_CLOUD
|
#ifdef FEATURE_CLOUD
|
||||||
bootLabel.redraw("cloud");
|
bootLabel.redraw("cloud");
|
||||||
initCloud();
|
initCloud();
|
||||||
@ -266,36 +208,6 @@ extern "C" void app_main()
|
|||||||
performance.lastTime = now;
|
performance.lastTime = now;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef FEATURE_CAN
|
|
||||||
if (!lastCanParse || now - *lastCanParse >= 1000ms/settings.boardcomputerHardware.timersSettings.canReceiveRate)
|
|
||||||
{
|
|
||||||
//can::tryParseCanInput();
|
|
||||||
can::parseCanInput();
|
|
||||||
|
|
||||||
lastCanParse = now;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef FEATURE_SERIAL
|
|
||||||
for (Controller &controller : controllers)
|
|
||||||
controller.parser.update();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
handleSerial();
|
|
||||||
|
|
||||||
#ifdef FEATURE_OTA
|
|
||||||
handleOta();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef FEATURE_BLE
|
|
||||||
if (!lastBleUpdate || now - *lastBleUpdate >= 250ms)
|
|
||||||
{
|
|
||||||
handleBle();
|
|
||||||
|
|
||||||
lastBleUpdate = now;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef FEATURE_ESPNOW
|
#ifdef FEATURE_ESPNOW
|
||||||
espnow::handle();
|
espnow::handle();
|
||||||
#endif
|
#endif
|
||||||
@ -316,10 +228,6 @@ extern "C" void app_main()
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef FEATURE_WEBSERVER
|
|
||||||
handleWebserver();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef FEATURE_BMS
|
#ifdef FEATURE_BMS
|
||||||
bms::update();
|
bms::update();
|
||||||
#endif
|
#endif
|
||||||
|
@ -6,7 +6,6 @@
|
|||||||
|
|
||||||
// local includes
|
// local includes
|
||||||
#include "globals.h"
|
#include "globals.h"
|
||||||
|
|
||||||
#ifdef FEATURE_CAN
|
#ifdef FEATURE_CAN
|
||||||
#include "can.h"
|
#include "can.h"
|
||||||
#endif
|
#endif
|
||||||
@ -19,6 +18,8 @@ void initPotis()
|
|||||||
raw_brems = std::nullopt;
|
raw_brems = std::nullopt;
|
||||||
gas = std::nullopt;
|
gas = std::nullopt;
|
||||||
brems = std::nullopt;
|
brems = std::nullopt;
|
||||||
|
|
||||||
|
readPotis();
|
||||||
}
|
}
|
||||||
|
|
||||||
void readPotis()
|
void readPotis()
|
||||||
|
@ -140,9 +140,6 @@ constexpr Settings::BoardcomputerHardware::TimersSettings defaultTimersSettings
|
|||||||
.statsUpdateRate = 50,
|
.statsUpdateRate = 50,
|
||||||
.displayUpdateRate = 50,
|
.displayUpdateRate = 50,
|
||||||
.displayRedrawRate = 50,
|
.displayRedrawRate = 50,
|
||||||
#ifdef FEATURE_CAN
|
|
||||||
.canReceiveRate = 100,
|
|
||||||
#endif
|
|
||||||
#ifdef FEATURE_CLOUD
|
#ifdef FEATURE_CLOUD
|
||||||
.cloudCollectRate = 100,
|
.cloudCollectRate = 100,
|
||||||
.cloudSendRate = 1,
|
.cloudSendRate = 1,
|
||||||
|
27
main/serial_bobby.cpp
Normal file
27
main/serial_bobby.cpp
Normal file
@ -0,0 +1,27 @@
|
|||||||
|
#include "serial_bobby.h"
|
||||||
|
|
||||||
|
// local includes
|
||||||
|
#include "globals.h"
|
||||||
|
#include "screens.h"
|
||||||
|
|
||||||
|
#ifdef FEATURE_SERIAL
|
||||||
|
|
||||||
|
void initSerial()
|
||||||
|
{
|
||||||
|
bootLabel.redraw("front Serial begin");
|
||||||
|
controllers.front.serial.get().begin(38400, SERIAL_8N1, PINS_RX1, PINS_TX1);
|
||||||
|
|
||||||
|
bootLabel.redraw("back Serial begin");
|
||||||
|
controllers.back.serial.get().begin(38400, SERIAL_8N1, PINS_RX2, PINS_TX2);
|
||||||
|
|
||||||
|
bootLabel.redraw("swap front back");
|
||||||
|
updateSwapFrontBack();
|
||||||
|
}
|
||||||
|
|
||||||
|
void updateSerial()
|
||||||
|
{
|
||||||
|
for (Controller &controller : controllers)
|
||||||
|
controller.parser.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
8
main/serial_bobby.h
Normal file
8
main/serial_bobby.h
Normal file
@ -0,0 +1,8 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#ifdef FEATURE_SERIAL
|
||||||
|
|
||||||
|
void initSerial();
|
||||||
|
void updateSerial();
|
||||||
|
|
||||||
|
#endif
|
@ -107,9 +107,6 @@ struct Settings
|
|||||||
int16_t statsUpdateRate;
|
int16_t statsUpdateRate;
|
||||||
int16_t displayUpdateRate;
|
int16_t displayUpdateRate;
|
||||||
int16_t displayRedrawRate;
|
int16_t displayRedrawRate;
|
||||||
#ifdef FEATURE_CAN
|
|
||||||
int16_t canReceiveRate;
|
|
||||||
#endif
|
|
||||||
#ifdef FEATURE_CLOUD
|
#ifdef FEATURE_CLOUD
|
||||||
int16_t cloudCollectRate;
|
int16_t cloudCollectRate;
|
||||||
int16_t cloudSendRate;
|
int16_t cloudSendRate;
|
||||||
@ -303,9 +300,6 @@ void Settings::executeForEveryCommonSetting(T &&callable)
|
|||||||
callable("statsUpdateRate", boardcomputerHardware.timersSettings.statsUpdateRate);
|
callable("statsUpdateRate", boardcomputerHardware.timersSettings.statsUpdateRate);
|
||||||
callable("displayUpdateRa", boardcomputerHardware.timersSettings.displayUpdateRate);
|
callable("displayUpdateRa", boardcomputerHardware.timersSettings.displayUpdateRate);
|
||||||
callable("displayRedrawRa", boardcomputerHardware.timersSettings.displayRedrawRate);
|
callable("displayRedrawRa", boardcomputerHardware.timersSettings.displayRedrawRate);
|
||||||
#ifdef FEATURE_CAN
|
|
||||||
callable("canReceiveRate", boardcomputerHardware.timersSettings.canReceiveRate);
|
|
||||||
#endif
|
|
||||||
#ifdef FEATURE_CLOUD
|
#ifdef FEATURE_CLOUD
|
||||||
callable("cloudCollectRat", boardcomputerHardware.timersSettings.cloudCollectRate);
|
callable("cloudCollectRat", boardcomputerHardware.timersSettings.cloudCollectRate);
|
||||||
callable("cloudSendRate", boardcomputerHardware.timersSettings.cloudSendRate);
|
callable("cloudSendRate", boardcomputerHardware.timersSettings.cloudSendRate);
|
||||||
|
@ -41,6 +41,22 @@
|
|||||||
#ifdef FEATURE_BLUETOOTH
|
#ifdef FEATURE_BLUETOOTH
|
||||||
#include "bluetooth_bobby.h"
|
#include "bluetooth_bobby.h"
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef FEATURE_CAN
|
||||||
|
#include "can.h"
|
||||||
|
#endif
|
||||||
|
#include "debuginputhandler.h"
|
||||||
|
#ifdef FEATURE_SERIAL
|
||||||
|
#include "serial_bobby.h"
|
||||||
|
#endif
|
||||||
|
#ifdef FEATURE_OTA
|
||||||
|
#include "ota.h"
|
||||||
|
#endif
|
||||||
|
#ifdef FEATURE_BLE
|
||||||
|
#include "ble_bobby.h"
|
||||||
|
#endif
|
||||||
|
#ifdef FEATURE_WEBSERVER
|
||||||
|
#include "webserver.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
using namespace std::chrono_literals;
|
using namespace std::chrono_literals;
|
||||||
|
|
||||||
@ -49,36 +65,52 @@ constexpr const char * const TAG = "TASKS";
|
|||||||
|
|
||||||
espcpputils::SchedulerTask schedulerTasksArr[] {
|
espcpputils::SchedulerTask schedulerTasksArr[] {
|
||||||
espcpputils::SchedulerTask { "wifi", wifi_begin, wifi_update, 100ms },
|
espcpputils::SchedulerTask { "wifi", wifi_begin, wifi_update, 100ms },
|
||||||
espcpputils::SchedulerTask { "input", InputDispatcher::init, InputDispatcher::update, {} },
|
espcpputils::SchedulerTask { "input", InputDispatcher::init, InputDispatcher::update, 20ms },
|
||||||
#ifdef FEATURE_DPAD
|
#ifdef FEATURE_DPAD
|
||||||
espcpputils::SchedulerTask { "dpad", dpad::init, dpad::update, {} },
|
espcpputils::SchedulerTask { "dpad", dpad::init, dpad::update, 20ms },
|
||||||
#endif
|
#endif
|
||||||
#ifdef FEATURE_DPAD_3WIRESW
|
#ifdef FEATURE_DPAD_3WIRESW
|
||||||
espcpputils::SchedulerTask { "dpad3wire", dpad3wire::init, dpad3wire::update, {} },
|
espcpputils::SchedulerTask { "dpad3wire", dpad3wire::init, dpad3wire::update, 20ms },
|
||||||
#endif
|
#endif
|
||||||
#ifdef FEATURE_DPAD_5WIRESW
|
#ifdef FEATURE_DPAD_5WIRESW
|
||||||
espcpputils::SchedulerTask { "dpad5wire", dpad5wire::init, dpad5wire::update, {} },
|
espcpputils::SchedulerTask { "dpad5wire", dpad5wire::init, dpad5wire::update, 20ms },
|
||||||
#endif
|
#endif
|
||||||
#ifdef FEATURE_DPAD_5WIRESW_2OUT
|
#ifdef FEATURE_DPAD_5WIRESW_2OUT
|
||||||
espcpputils::SchedulerTask { "dpad5wire_2out", dpad5wire_2out::init, dpad5wire_2out::update, {} },
|
espcpputils::SchedulerTask { "dpad5wire_2out", dpad5wire_2out::init, dpad5wire_2out::update, 20ms },
|
||||||
#endif
|
#endif
|
||||||
#ifdef FEATURE_DPAD_6WIRESW
|
#ifdef FEATURE_DPAD_6WIRESW
|
||||||
espcpputils::SchedulerTask { "dpad6wire", dpad6wire::init, dpad6wire::update, {} },
|
espcpputils::SchedulerTask { "dpad6wire", dpad6wire::init, dpad6wire::update, 20ms },
|
||||||
#endif
|
#endif
|
||||||
#ifdef FEATURE_ROTARY
|
#ifdef FEATURE_ROTARY
|
||||||
espcpputils::SchedulerTask { "rotary", initRotary, updateRotary, {} },
|
espcpputils::SchedulerTask { "rotary", initRotary, updateRotary, 20ms },
|
||||||
#endif
|
#endif
|
||||||
#ifdef FEATURE_MOSFETS
|
#ifdef FEATURE_MOSFETS
|
||||||
espcpputils::SchedulerTask { "mosfets", init_mosfets, update_mosfets, {} },
|
espcpputils::SchedulerTask { "mosfets", init_mosfets, update_mosfets, 100ms },
|
||||||
#endif
|
#endif
|
||||||
espcpputils::SchedulerTask { "wifi", wifi_begin, wifi_update, 100ms },
|
espcpputils::SchedulerTask { "wifi", wifi_begin, wifi_update, 100ms },
|
||||||
#ifdef FEATURE_NTP
|
#ifdef FEATURE_NTP
|
||||||
espcpputils::SchedulerTask { "time", initTime, updateTime, 100ms },
|
espcpputils::SchedulerTask { "time", initTime, updateTime, 100ms },
|
||||||
#endif
|
#endif
|
||||||
espcpputils::SchedulerTask { "potis", initPotis, readPotis, 20ms },
|
espcpputils::SchedulerTask { "potis", initPotis, readPotis, 20ms },
|
||||||
#ifdef FEATURE_BLUETOOTH
|
#ifdef FEATURE_BLUETOOTH
|
||||||
espcpputils::SchedulerTask { "bluetooth", bluetooth_init, bluetooth_update, 100ms },
|
espcpputils::SchedulerTask { "bluetooth", bluetooth_init, bluetooth_update, 100ms },
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef FEATURE_CAN
|
||||||
|
espcpputils::SchedulerTask { "can", can::initCan, can::parseCanInput, 50ms },
|
||||||
|
#endif
|
||||||
|
espcpputils::SchedulerTask { "debuginput", initDebugInput, handleDebugInput, 50ms },
|
||||||
|
#ifdef FEATURE_SERIAL
|
||||||
|
espcpputils::SchedulerTask { "serial", initSerial, updateSerial, 50ms },
|
||||||
|
#endif
|
||||||
|
#ifdef FEATURE_OTA
|
||||||
|
espcpputils::SchedulerTask { "ota", initOta, handleOta, 50ms },
|
||||||
|
#endif
|
||||||
|
#ifdef FEATURE_BLE
|
||||||
|
espcpputils::SchedulerTask { "ble", initBle, handleBle, 100ms },
|
||||||
|
#endif
|
||||||
|
#ifdef FEATURE_WEBSERVER
|
||||||
|
espcpputils::SchedulerTask { "webserver", initWebserver, handleWebserver, 100ms },
|
||||||
|
#endif
|
||||||
};
|
};
|
||||||
} // namespace
|
} // namespace
|
||||||
|
|
||||||
|
@ -428,9 +428,6 @@ char TEXT_MODEUPDATERATE[] = "Mode update rate";
|
|||||||
char TEXT_STATSUPDATERATE[] = "Stats update rate";
|
char TEXT_STATSUPDATERATE[] = "Stats update rate";
|
||||||
char TEXT_DISPLAYUPDATERATE[] = "Display update rate";
|
char TEXT_DISPLAYUPDATERATE[] = "Display update rate";
|
||||||
char TEXT_DISPLAYREDRAWRATE[] = "Display redraw rate";
|
char TEXT_DISPLAYREDRAWRATE[] = "Display redraw rate";
|
||||||
#ifdef FEATURE_CAN
|
|
||||||
char TEXT_CANRECEIVERATE[] = "CAN receive rate";
|
|
||||||
#endif
|
|
||||||
//char TEXT_BACK[] = "Back";
|
//char TEXT_BACK[] = "Back";
|
||||||
|
|
||||||
//TimeSettingsMenu
|
//TimeSettingsMenu
|
||||||
|
@ -428,9 +428,6 @@ extern char TEXT_MODEUPDATERATE[];
|
|||||||
extern char TEXT_STATSUPDATERATE[];
|
extern char TEXT_STATSUPDATERATE[];
|
||||||
extern char TEXT_DISPLAYUPDATERATE[];
|
extern char TEXT_DISPLAYUPDATERATE[];
|
||||||
extern char TEXT_DISPLAYREDRAWRATE[];
|
extern char TEXT_DISPLAYREDRAWRATE[];
|
||||||
#ifdef FEATURE_CAN
|
|
||||||
extern char TEXT_CANRECEIVERATE[];
|
|
||||||
#endif
|
|
||||||
//extern char TEXT_BACK[];
|
//extern char TEXT_BACK[];
|
||||||
|
|
||||||
//TimeSettingsMenu
|
//TimeSettingsMenu
|
||||||
|
Reference in New Issue
Block a user