@ -167,6 +167,7 @@ set(headers
|
||||
modes/motortestmode.h
|
||||
modes/remotecontrolmode.h
|
||||
modes/tempomatmode.h
|
||||
mosfets.h
|
||||
newsettings.h
|
||||
ota.h
|
||||
presets.h
|
||||
@ -179,6 +180,7 @@ set(headers
|
||||
statistics.h
|
||||
statustexthelper.h
|
||||
stringsettings.h
|
||||
taskmanager.h
|
||||
texts.h
|
||||
time_bobbycar.h
|
||||
types.h
|
||||
@ -367,6 +369,7 @@ set(sources
|
||||
modes/motortestmode.cpp
|
||||
modes/remotecontrolmode.cpp
|
||||
modes/tempomatmode.cpp
|
||||
mosfets.cpp
|
||||
newsettings.cpp
|
||||
ota.cpp
|
||||
presets.cpp
|
||||
@ -379,6 +382,7 @@ set(sources
|
||||
statistics.cpp
|
||||
statustexthelper.cpp
|
||||
stringsettings.cpp
|
||||
taskmanager.cpp
|
||||
texts.cpp
|
||||
time_bobbycar.cpp
|
||||
types.cpp
|
||||
|
@ -16,6 +16,11 @@ int upPressRepeat{};
|
||||
std::optional<espchrono::millis_clock::time_point> downPressedSince;
|
||||
int downPressRepeat{};
|
||||
|
||||
void InputDispatcher::init()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void InputDispatcher::update()
|
||||
{
|
||||
if (upPressedSince && espchrono::ago(*upPressedSince) > (upPressRepeat > 2 ? 50ms : 400ms))
|
||||
|
@ -32,6 +32,8 @@ extern int downPressRepeat;
|
||||
class InputDispatcher
|
||||
{
|
||||
public:
|
||||
static void init();
|
||||
|
||||
static void update();
|
||||
|
||||
static void rotate(int offset);
|
||||
|
101
main/main.cpp
101
main/main.cpp
@ -8,7 +8,6 @@ constexpr const char * const TAG = "BOBBY";
|
||||
#include <cstdio>
|
||||
|
||||
// esp-idf includes
|
||||
#include <esp_wifi_types.h>
|
||||
#include <esp_log.h>
|
||||
|
||||
// Arduino includes
|
||||
@ -18,6 +17,7 @@ constexpr const char * const TAG = "BOBBY";
|
||||
#include <espchrono.h>
|
||||
using namespace std::chrono_literals;
|
||||
#include <espwifistack.h>
|
||||
#include <schedulertask.h>
|
||||
|
||||
// local includes
|
||||
#include "bobbycar-common.h"
|
||||
@ -25,22 +25,6 @@ using namespace std::chrono_literals;
|
||||
#include "macros_bobbycar.h"
|
||||
#include "globals.h"
|
||||
#include "screens.h"
|
||||
#include "dpad.h"
|
||||
#ifdef FEATURE_DPAD_3WIRESW
|
||||
#include "dpad3wire.h"
|
||||
#endif
|
||||
#ifdef FEATURE_DPAD_5WIRESW
|
||||
#include "dpad5wire.h"
|
||||
#endif
|
||||
#ifdef FEATURE_DPAD_5WIRESW_2OUT
|
||||
#include "dpad5wire_2out.h"
|
||||
#endif
|
||||
#ifdef FEATURE_DPAD_6WIRESW
|
||||
#include "dpad6wire.h"
|
||||
#endif
|
||||
#ifdef FEATURE_ROTARY
|
||||
#include "rotary.h"
|
||||
#endif
|
||||
#include "serialhandler.h"
|
||||
#ifdef FEATURE_OTA
|
||||
#include "ota.h"
|
||||
@ -81,9 +65,9 @@ using namespace std::chrono_literals;
|
||||
#endif
|
||||
#include "drivingstatistics.h"
|
||||
#include "newsettings.h"
|
||||
#include "taskmanager.h"
|
||||
|
||||
namespace {
|
||||
std::optional<espchrono::millis_clock::time_point> lastWifiUpdate;
|
||||
std::optional<espchrono::millis_clock::time_point> lastPotiRead;
|
||||
std::optional<espchrono::millis_clock::time_point> lastModeUpdate;
|
||||
std::optional<espchrono::millis_clock::time_point> lastStatsUpdate;
|
||||
@ -151,54 +135,11 @@ extern "C" void app_main()
|
||||
else
|
||||
ESP_LOGE("MAIN", "get_default_mac_addr() failed: %.*s", result.error().size(), result.error().data());
|
||||
|
||||
bootLabel.redraw("wifi");
|
||||
wifi_begin();
|
||||
|
||||
#ifdef FEATURE_DPAD
|
||||
bootLabel.redraw("dpad");
|
||||
dpad::init();
|
||||
#endif
|
||||
|
||||
#ifdef FEATURE_DPAD_3WIRESW
|
||||
bootLabel.redraw("dpad3wire");
|
||||
dpad3wire::init();
|
||||
#endif
|
||||
|
||||
#ifdef FEATURE_DPAD_5WIRESW
|
||||
bootLabel.redraw("dpad5wire");
|
||||
dpad5wire::init();
|
||||
#endif
|
||||
|
||||
#ifdef FEATURE_DPAD_5WIRESW_2OUT
|
||||
bootLabel.redraw("dpad5wire_2out");
|
||||
dpad5wire_2out::init();
|
||||
#endif
|
||||
|
||||
#ifdef FEATURE_DPAD_6WIRESW
|
||||
bootLabel.redraw("dpad6wire");
|
||||
dpad6wire::init();
|
||||
#endif
|
||||
|
||||
#ifdef FEATURE_ROTARY
|
||||
bootLabel.redraw("rotary");
|
||||
initRotary();
|
||||
#endif
|
||||
|
||||
#ifdef FEATURE_MOSFETS
|
||||
bootLabel.redraw("mosfets");
|
||||
pinMode(PINS_MOSFET0, OUTPUT);
|
||||
pinMode(PINS_MOSFET1, OUTPUT);
|
||||
pinMode(PINS_MOSFET2, OUTPUT);
|
||||
|
||||
digitalWrite(PINS_MOSFET0, LOW);
|
||||
digitalWrite(PINS_MOSFET1, LOW);
|
||||
digitalWrite(PINS_MOSFET2, LOW);
|
||||
#endif
|
||||
|
||||
#ifdef FEATURE_SERIAL
|
||||
bootLabel.redraw("swap front back");
|
||||
updateSwapFrontBack();
|
||||
#endif
|
||||
for (const auto &task : schedulerTasks)
|
||||
{
|
||||
bootLabel.redraw(task.name());
|
||||
task.setup();
|
||||
}
|
||||
|
||||
#ifdef FEATURE_BLUETOOTH
|
||||
if (settings.bluetoothSettings.autoBluetoothMode == BluetoothMode::Master)
|
||||
@ -231,6 +172,9 @@ extern "C" void app_main()
|
||||
|
||||
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
|
||||
@ -296,33 +240,12 @@ extern "C" void app_main()
|
||||
{
|
||||
const auto now = espchrono::millis_clock::now();
|
||||
|
||||
if (!lastWifiUpdate || now - *lastWifiUpdate >= 100ms)
|
||||
for (auto &schedulerTask : schedulerTasks)
|
||||
{
|
||||
wifi_update();
|
||||
schedulerTask.loop();
|
||||
|
||||
lastWifiUpdate = now;
|
||||
}
|
||||
|
||||
InputDispatcher::update();
|
||||
|
||||
#ifdef FEATURE_DPAD
|
||||
dpad::update();
|
||||
#endif
|
||||
|
||||
#ifdef FEATURE_DPAD_3WIRESW
|
||||
dpad3wire::update();
|
||||
#endif
|
||||
|
||||
#ifdef FEATURE_DPAD_5WIRESW
|
||||
dpad5wire::update();
|
||||
#endif
|
||||
#ifdef FEATURE_DPAD_5WIRESW_2OUT
|
||||
dpad5wire_2out::update();
|
||||
#endif
|
||||
#ifdef FEATURE_DPAD_6WIRESW
|
||||
dpad6wire::update();
|
||||
#endif
|
||||
|
||||
if (!lastPotiRead || now - *lastPotiRead >= 1000ms/settings.boardcomputerHardware.timersSettings.potiReadRate)
|
||||
{
|
||||
readPotis();
|
||||
|
22
main/mosfets.cpp
Normal file
22
main/mosfets.cpp
Normal file
@ -0,0 +1,22 @@
|
||||
#include "mosfets.h"
|
||||
|
||||
// Arduino includes
|
||||
#include <Arduino.h>
|
||||
|
||||
#ifdef FEATURE_MOSFETS
|
||||
void init_mosfets()
|
||||
{
|
||||
pinMode(PINS_MOSFET0, OUTPUT);
|
||||
pinMode(PINS_MOSFET1, OUTPUT);
|
||||
pinMode(PINS_MOSFET2, OUTPUT);
|
||||
|
||||
digitalWrite(PINS_MOSFET0, LOW);
|
||||
digitalWrite(PINS_MOSFET1, LOW);
|
||||
digitalWrite(PINS_MOSFET2, LOW);
|
||||
}
|
||||
|
||||
void update_mosfets()
|
||||
{
|
||||
|
||||
}
|
||||
#endif
|
6
main/mosfets.h
Normal file
6
main/mosfets.h
Normal file
@ -0,0 +1,6 @@
|
||||
#pragma once
|
||||
|
||||
#ifdef FEATURE_MOSFETS
|
||||
void init_mosfets();
|
||||
void update_mosfets();
|
||||
#endif
|
@ -84,5 +84,10 @@ void initRotary()
|
||||
attachInterrupt(decltype(rotary)::ClkPin, updateRotate, CHANGE);
|
||||
attachInterrupt(decltype(rotary)::SwPin, updateSwitch, CHANGE);
|
||||
}
|
||||
|
||||
void updateRotary()
|
||||
{
|
||||
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
82
main/taskmanager.cpp
Normal file
82
main/taskmanager.cpp
Normal file
@ -0,0 +1,82 @@
|
||||
#include "taskmanager.h"
|
||||
|
||||
#include "sdkconfig.h"
|
||||
|
||||
// system includes
|
||||
#include <iterator>
|
||||
#include <chrono>
|
||||
|
||||
// esp-idf includes
|
||||
#include <esp_log.h>
|
||||
|
||||
// 3rdparty lib includes
|
||||
#include <schedulertask.h>
|
||||
|
||||
// local includes
|
||||
#include "wifi_bobbycar.h"
|
||||
#include "buttons.h"
|
||||
#include "dpad.h"
|
||||
#ifdef FEATURE_DPAD_3WIRESW
|
||||
#include "dpad3wire.h"
|
||||
#endif
|
||||
#ifdef FEATURE_DPAD_5WIRESW
|
||||
#include "dpad5wire.h"
|
||||
#endif
|
||||
#ifdef FEATURE_DPAD_5WIRESW_2OUT
|
||||
#include "dpad5wire_2out.h"
|
||||
#endif
|
||||
#ifdef FEATURE_DPAD_6WIRESW
|
||||
#include "dpad6wire.h"
|
||||
#endif
|
||||
#ifdef FEATURE_ROTARY
|
||||
#include "rotary.h"
|
||||
#endif
|
||||
#ifdef FEATURE_MOSFETS
|
||||
#include "mosfets.h"
|
||||
#endif
|
||||
|
||||
using namespace std::chrono_literals;
|
||||
|
||||
namespace {
|
||||
constexpr const char * const TAG = "TASKS";
|
||||
|
||||
espcpputils::SchedulerTask schedulerTasksArr[] {
|
||||
espcpputils::SchedulerTask { "wifi", wifi_begin, wifi_update, 100ms },
|
||||
espcpputils::SchedulerTask { "input", InputDispatcher::init, InputDispatcher::update, {} },
|
||||
#ifdef FEATURE_DPAD
|
||||
espcpputils::SchedulerTask { "dpad", dpad::init, dpad::update, {} },
|
||||
#endif
|
||||
#ifdef FEATURE_DPAD_3WIRESW
|
||||
espcpputils::SchedulerTask { "dpad3wire", dpad3wire::init, dpad3wire::update, {} },
|
||||
#endif
|
||||
#ifdef FEATURE_DPAD_5WIRESW
|
||||
espcpputils::SchedulerTask { "dpad5wire", dpad5wire::init, dpad5wire::update, {} },
|
||||
#endif
|
||||
#ifdef FEATURE_DPAD_5WIRESW_2OUT
|
||||
espcpputils::SchedulerTask { "dpad5wire_2out", dpad5wire_2out::init, dpad5wire_2out::update, {} },
|
||||
#endif
|
||||
#ifdef FEATURE_DPAD_6WIRESW
|
||||
espcpputils::SchedulerTask { "dpad6wire", dpad6wire::init, dpad6wire::update, {} },
|
||||
#endif
|
||||
#ifdef FEATURE_ROTARY
|
||||
espcpputils::SchedulerTask { "rotary", initRotary, updateRotary, {} },
|
||||
#endif
|
||||
#ifdef FEATURE_MOSFETS
|
||||
espcpputils::SchedulerTask { "mosfets", init_mosfets, update_mosfets, {} },
|
||||
#endif
|
||||
};
|
||||
} // namespace
|
||||
|
||||
cpputils::ArrayView<espcpputils::SchedulerTask> schedulerTasks{std::begin(schedulerTasksArr), std::end(schedulerTasksArr)};
|
||||
|
||||
void sched_pushStats(bool printTasks)
|
||||
{
|
||||
if (printTasks)
|
||||
ESP_LOGI(TAG, "begin listing tasks...");
|
||||
|
||||
for (auto &schedulerTask : schedulerTasks)
|
||||
schedulerTask.pushStats(printTasks);
|
||||
|
||||
if (printTasks)
|
||||
ESP_LOGI(TAG, "end listing tasks");
|
||||
}
|
11
main/taskmanager.h
Normal file
11
main/taskmanager.h
Normal file
@ -0,0 +1,11 @@
|
||||
#pragma once
|
||||
|
||||
// 3rdparty lib includes
|
||||
#include <arrayview.h>
|
||||
|
||||
// forward declares
|
||||
namespace espcpputils { class SchedulerTask; }
|
||||
|
||||
extern cpputils::ArrayView<espcpputils::SchedulerTask> schedulerTasks;
|
||||
|
||||
void sched_pushStats(bool printTasks);
|
Reference in New Issue
Block a user