ADC and button input via can
This commit is contained in:
@ -68,6 +68,7 @@ build_flags =
|
||||
-DPINS_TX1=5
|
||||
-DPINS_RX2=25
|
||||
-DPINS_TX2=26
|
||||
-DFEATURE_ADC_IN
|
||||
-DFEATURE_MOSFETS
|
||||
-DPINS_MOSFET0=18
|
||||
-DPINS_MOSFET1=19
|
||||
@ -105,6 +106,7 @@ lib_compat_mode = ${common_env_data.lib_compat_mode}
|
||||
build_unflags = ${common_env_data.build_unflags}
|
||||
build_flags =
|
||||
${common_env_data.build_flags}
|
||||
-DFEATURE_ADC_IN
|
||||
-DPINS_GAS=34
|
||||
-DPINS_BREMS=35
|
||||
; -DPINS_LED=23
|
||||
@ -339,6 +341,7 @@ build_flags =
|
||||
-DPINS_TX1=25
|
||||
-DPINS_RX2=23
|
||||
-DPINS_TX2=34
|
||||
-DFEATURE_ADC_IN
|
||||
-DPINS_GAS=35
|
||||
-DPINS_BREMS=33
|
||||
-DDEFAULT_GASMIN=0
|
||||
@ -414,6 +417,7 @@ lib_compat_mode = ${common_env_data.lib_compat_mode}
|
||||
build_unflags = ${common_env_data.build_unflags}
|
||||
build_flags =
|
||||
${common_env_data.build_flags}
|
||||
-DFEATURE_ADC_IN
|
||||
-DPINS_GAS=33
|
||||
-DPINS_BREMS=35
|
||||
-DILI9341_DRIVER=1
|
||||
|
@ -3,25 +3,16 @@
|
||||
#include <HardwareSerial.h>
|
||||
|
||||
#include "actioninterface.h"
|
||||
#include "globals.h"
|
||||
#include "presets.h"
|
||||
#include "settingsutils.h"
|
||||
|
||||
namespace {
|
||||
template<uint8_t profile>
|
||||
template<uint8_t index>
|
||||
class SwitchProfileAction : public virtual ActionInterface
|
||||
{
|
||||
public:
|
||||
void triggered() override
|
||||
{
|
||||
settings = presets::defaultSettings;
|
||||
|
||||
if (settingsPersister.openProfile(profile))
|
||||
{
|
||||
if (!settingsPersister.load(settings))
|
||||
Serial.println("SwitchProfileAction::triggered() load failed");
|
||||
}
|
||||
else
|
||||
Serial.println("SwitchProfileAction::triggered() openProfile failed");
|
||||
switchProfile(index);
|
||||
}
|
||||
};
|
||||
}
|
||||
|
@ -4,9 +4,11 @@
|
||||
#include "utils.h"
|
||||
|
||||
namespace {
|
||||
#ifdef FEATURE_SERIAL
|
||||
class UpdateSwapFrontBackAction : public virtual ActionInterface
|
||||
{
|
||||
public:
|
||||
void triggered() override { updateSwapFrontBack(); }
|
||||
};
|
||||
#endif
|
||||
}
|
||||
|
Submodule src/bobbycar-protocol updated: 2e0f97d6dd...2c6fb114f2
80
src/buttons.h
Normal file
80
src/buttons.h
Normal file
@ -0,0 +1,80 @@
|
||||
#pragma once
|
||||
|
||||
// Arduino includes
|
||||
#include <Arduino.h>
|
||||
|
||||
// local includes
|
||||
#include "types.h"
|
||||
#include "settingsutils.h"
|
||||
|
||||
namespace {
|
||||
|
||||
int rotated{};
|
||||
bool requestFullRedraw{};
|
||||
|
||||
bool confirmButtonPressed{};
|
||||
bool confirmButtonLongPressed{};
|
||||
bool backButtonPressed{};
|
||||
bool backButtonLongPressed{};
|
||||
|
||||
class InputDispatcher
|
||||
{
|
||||
public:
|
||||
static void rotate(int offset)
|
||||
{
|
||||
rotated += offset;
|
||||
}
|
||||
|
||||
static void confirmButton(bool pressed)
|
||||
{
|
||||
static millis_t pressBegin = 0;
|
||||
|
||||
const auto now = millis();
|
||||
|
||||
if (pressed)
|
||||
pressBegin = now;
|
||||
else
|
||||
{
|
||||
const auto duration = now - pressBegin;
|
||||
|
||||
if (duration < 500)
|
||||
confirmButtonPressed = true;
|
||||
else if (duration < 2000)
|
||||
confirmButtonLongPressed = true;
|
||||
else
|
||||
requestFullRedraw = true;
|
||||
|
||||
pressBegin = 0;
|
||||
}
|
||||
}
|
||||
|
||||
static void backButton(bool pressed)
|
||||
{
|
||||
static millis_t pressBegin = 0;
|
||||
|
||||
const auto now = millis();
|
||||
|
||||
if (pressed)
|
||||
pressBegin = now;
|
||||
else
|
||||
{
|
||||
const auto duration = now - pressBegin;
|
||||
|
||||
if (duration < 500)
|
||||
backButtonPressed = true;
|
||||
else
|
||||
backButtonLongPressed = true;
|
||||
|
||||
pressBegin = 0;
|
||||
}
|
||||
}
|
||||
|
||||
static void profileButton(uint8_t index, bool pressed)
|
||||
{
|
||||
if (!pressed)
|
||||
return;
|
||||
|
||||
switchProfile(index);
|
||||
}
|
||||
};
|
||||
}
|
273
src/can.h
273
src/can.h
@ -1,6 +1,7 @@
|
||||
#pragma once
|
||||
|
||||
#include <cstring>
|
||||
#include <optional>
|
||||
|
||||
#include <driver/gpio.h>
|
||||
#include <driver/can.h>
|
||||
@ -11,8 +12,26 @@
|
||||
|
||||
#include "types.h"
|
||||
#include "globals.h"
|
||||
#include "buttons.h"
|
||||
|
||||
namespace can {
|
||||
namespace {
|
||||
std::optional<int16_t> can_gas, can_brems;
|
||||
millis_t last_can_gas{}, last_can_brems{};
|
||||
|
||||
struct CanButtonsState
|
||||
{
|
||||
bool up{};
|
||||
bool down{};
|
||||
bool confirm{};
|
||||
bool back{};
|
||||
bool profile0{};
|
||||
bool profile1{};
|
||||
bool profile2{};
|
||||
bool profile3{};
|
||||
};
|
||||
CanButtonsState lastButtonsState;
|
||||
|
||||
void initCan()
|
||||
{
|
||||
Serial.println("initCan()");
|
||||
@ -59,7 +78,7 @@ void initCan()
|
||||
}
|
||||
|
||||
template<bool isBack>
|
||||
bool parseCanMessage(const can_message_t &message, Controller &controller)
|
||||
bool parseMotorControllerCanMessage(const can_message_t &message, Controller &controller)
|
||||
{
|
||||
switch (message.identifier)
|
||||
{
|
||||
@ -135,7 +154,68 @@ bool parseCanMessage(const can_message_t &message, Controller &controller)
|
||||
return false;
|
||||
}
|
||||
|
||||
bool parseCanInput()
|
||||
bool parseBoardcomputerCanMessage(const can_message_t &message)
|
||||
{
|
||||
switch (message.identifier)
|
||||
{
|
||||
using namespace bobbycar::protocol::can;
|
||||
case Boardcomputer::Command::ButtonPress:
|
||||
{
|
||||
const auto canButtonBits = *((uint16_t*)message.data);
|
||||
CanButtonsState newState {
|
||||
.up = bool(canButtonBits & Boardcomputer::ButtonUp),
|
||||
.down = bool(canButtonBits & Boardcomputer::ButtonDown),
|
||||
.confirm = bool(canButtonBits & Boardcomputer::ButtonConfirm),
|
||||
.back = bool(canButtonBits & Boardcomputer::ButtonBack),
|
||||
.profile0 = bool(canButtonBits & Boardcomputer::ButtonProfile0),
|
||||
.profile1 = bool(canButtonBits & Boardcomputer::ButtonProfile1),
|
||||
.profile2 = bool(canButtonBits & Boardcomputer::ButtonProfile2),
|
||||
.profile3 = bool(canButtonBits & Boardcomputer::ButtonProfile3),
|
||||
};
|
||||
|
||||
if (lastButtonsState.up != newState.up)
|
||||
if (newState.up)
|
||||
InputDispatcher::rotate(-1);
|
||||
|
||||
if (lastButtonsState.down != newState.down)
|
||||
if (newState.down)
|
||||
InputDispatcher::rotate(1);
|
||||
|
||||
if (lastButtonsState.confirm != newState.confirm)
|
||||
InputDispatcher::confirmButton(newState.confirm);
|
||||
|
||||
if (lastButtonsState.back != newState.back)
|
||||
InputDispatcher::backButton(newState.back);
|
||||
|
||||
if (lastButtonsState.profile0 != newState.profile0)
|
||||
InputDispatcher::profileButton(0, newState.profile0);
|
||||
|
||||
if (lastButtonsState.profile1 != newState.profile1)
|
||||
InputDispatcher::profileButton(1, newState.profile1);
|
||||
|
||||
if (lastButtonsState.profile2 != newState.profile2)
|
||||
InputDispatcher::profileButton(2, newState.profile2);
|
||||
|
||||
if (lastButtonsState.profile3 != newState.profile3)
|
||||
InputDispatcher::profileButton(3, newState.profile3);
|
||||
|
||||
lastButtonsState = newState;
|
||||
break;
|
||||
}
|
||||
case Boardcomputer::Command::RawGas:
|
||||
can_gas = *((int16_t*)message.data);
|
||||
last_can_gas = millis();
|
||||
break;
|
||||
case Boardcomputer::Command::RawBrems:
|
||||
can_brems = *((int16_t*)message.data);
|
||||
last_can_brems = millis();
|
||||
break;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool tryParseCanInput()
|
||||
{
|
||||
can_message_t message;
|
||||
if (const auto result = can_receive(&message, pdMS_TO_TICKS(50)); result != ESP_OK)
|
||||
@ -152,38 +232,51 @@ bool parseCanInput()
|
||||
return false;
|
||||
}
|
||||
|
||||
if (parseCanMessage<false>(message, controllers.front))
|
||||
{
|
||||
if (millis() - controllers.back.lastCanFeedback > 100)
|
||||
controllers.back.feedbackValid = false;
|
||||
Controller &front = settings.controllerHardware.swapFrontBack ? controllers.back : controllers.front;
|
||||
Controller &back = settings.controllerHardware.swapFrontBack ? controllers.front : controllers.back;
|
||||
|
||||
controllers.front.lastCanFeedback = millis();
|
||||
controllers.front.feedbackValid = true;
|
||||
if (parseMotorControllerCanMessage<false>(message, front))
|
||||
{
|
||||
if (millis() - back.lastCanFeedback > 100)
|
||||
back.feedbackValid = false;
|
||||
|
||||
front.lastCanFeedback = millis();
|
||||
front.feedbackValid = true;
|
||||
return true;
|
||||
}
|
||||
else
|
||||
{
|
||||
if (millis() - controllers.front.lastCanFeedback > 100)
|
||||
controllers.front.feedbackValid = false;
|
||||
if (millis() - front.lastCanFeedback > 100)
|
||||
front.feedbackValid = false;
|
||||
}
|
||||
|
||||
if (parseCanMessage<true>(message, controllers.back))
|
||||
if (parseMotorControllerCanMessage<true>(message, back))
|
||||
{
|
||||
controllers.back.lastCanFeedback = millis();
|
||||
controllers.back.feedbackValid = true;
|
||||
back.lastCanFeedback = millis();
|
||||
back.feedbackValid = true;
|
||||
return true;
|
||||
}
|
||||
else
|
||||
{
|
||||
if (millis() - controllers.back.lastCanFeedback > 100)
|
||||
controllers.back.feedbackValid = false;
|
||||
if (millis() - back.lastCanFeedback > 100)
|
||||
back.feedbackValid = false;
|
||||
}
|
||||
|
||||
if (parseBoardcomputerCanMessage(message))
|
||||
return true;
|
||||
|
||||
//Serial.printf("WARNING Unknown CAN info received .identifier = %u\r\n", message.identifier);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void parseCanInput()
|
||||
{
|
||||
for (int i = 0; i < 4; i++)
|
||||
if (!tryParseCanInput())
|
||||
break;
|
||||
}
|
||||
|
||||
void sendCanCommands()
|
||||
{
|
||||
constexpr auto send = [](uint32_t addr, auto value){
|
||||
@ -200,89 +293,129 @@ void sendCanCommands()
|
||||
return result;
|
||||
};
|
||||
|
||||
const Controller &front = settings.controllerHardware.swapFrontBack ? controllers.back : controllers.front;
|
||||
const Controller &back = settings.controllerHardware.swapFrontBack ? controllers.front : controllers.back;
|
||||
|
||||
using namespace bobbycar::protocol::can;
|
||||
|
||||
send(MotorController<false, false>::Command::InpTgt, controllers.front.command.left.pwm);
|
||||
send(MotorController<false, true>::Command::InpTgt, controllers.front.command.right.pwm);
|
||||
send(MotorController<true, false>::Command::InpTgt, controllers.back.command.left.pwm);
|
||||
send(MotorController<true, true>::Command::InpTgt, controllers.back.command.right.pwm);
|
||||
send(MotorController<false, false>::Command::InpTgt, front.command.left.pwm);
|
||||
send(MotorController<false, true>::Command::InpTgt, front.command.right.pwm);
|
||||
send(MotorController<true, false>::Command::InpTgt, back.command.left.pwm);
|
||||
send(MotorController<true, true>::Command::InpTgt, back.command.right.pwm);
|
||||
|
||||
uint16_t buttonLeds{};
|
||||
if (const auto index = settingsPersister.currentlyOpenProfileIndex())
|
||||
switch (*index)
|
||||
{
|
||||
case 0: buttonLeds |= Boardcomputer::ButtonProfile0; break;
|
||||
case 1: buttonLeds |= Boardcomputer::ButtonProfile1; break;
|
||||
case 2: buttonLeds |= Boardcomputer::ButtonProfile2; break;
|
||||
case 3: buttonLeds |= Boardcomputer::ButtonProfile3; break;
|
||||
}
|
||||
|
||||
static struct {
|
||||
struct {
|
||||
uint8_t freq = 0;
|
||||
uint8_t pattern = 0;
|
||||
} front, back;
|
||||
uint16_t buttonLeds{};
|
||||
} lastValues;
|
||||
|
||||
static int i{};
|
||||
|
||||
if (front.command.buzzer.freq != lastValues.front.freq ||
|
||||
front.command.buzzer.pattern != lastValues.front.pattern ||
|
||||
back.command.buzzer.freq != lastValues.back.freq ||
|
||||
back.command.buzzer.pattern != lastValues.back.pattern)
|
||||
i = 8;
|
||||
else if (buttonLeds != lastValues.buttonLeds)
|
||||
i = 10;
|
||||
|
||||
switch (i++)
|
||||
{
|
||||
case 0:
|
||||
send(MotorController<false, false>::Command::Enable, controllers.front.command.left.enable);
|
||||
send(MotorController<false, true>::Command::Enable, controllers.front.command.right.enable);
|
||||
send(MotorController<true, false>::Command::Enable, controllers.back.command.left.enable);
|
||||
send(MotorController<true, true>::Command::Enable, controllers.back.command.right.enable);
|
||||
send(MotorController<false, false>::Command::Enable, front.command.left.enable);
|
||||
send(MotorController<false, true>::Command::Enable, front.command.right.enable);
|
||||
send(MotorController<true, false>::Command::Enable, back.command.left.enable);
|
||||
send(MotorController<true, true>::Command::Enable, back.command.right.enable);
|
||||
break;
|
||||
case 1:
|
||||
send(MotorController<false, false>::Command::CtrlTyp, controllers.front.command.left.ctrlTyp);
|
||||
send(MotorController<false, true>::Command::CtrlTyp, controllers.front.command.right.ctrlTyp);
|
||||
send(MotorController<true, false>::Command::CtrlTyp, controllers.back.command.left.ctrlTyp);
|
||||
send(MotorController<true, true>::Command::CtrlTyp, controllers.back.command.right.ctrlTyp);
|
||||
send(MotorController<false, false>::Command::CtrlTyp, front.command.left.ctrlTyp);
|
||||
send(MotorController<false, true>::Command::CtrlTyp, front.command.right.ctrlTyp);
|
||||
send(MotorController<true, false>::Command::CtrlTyp, back.command.left.ctrlTyp);
|
||||
send(MotorController<true, true>::Command::CtrlTyp, back.command.right.ctrlTyp);
|
||||
break;
|
||||
case 2:
|
||||
send(MotorController<false, false>::Command::CtrlMod, controllers.front.command.left.ctrlMod);
|
||||
send(MotorController<false, true>::Command::CtrlMod, controllers.front.command.right.ctrlMod);
|
||||
send(MotorController<true, false>::Command::CtrlMod, controllers.back.command.left.ctrlMod);
|
||||
send(MotorController<true, true>::Command::CtrlMod, controllers.back.command.right.ctrlMod);
|
||||
send(MotorController<false, false>::Command::CtrlMod, front.command.left.ctrlMod);
|
||||
send(MotorController<false, true>::Command::CtrlMod, front.command.right.ctrlMod);
|
||||
send(MotorController<true, false>::Command::CtrlMod, back.command.left.ctrlMod);
|
||||
send(MotorController<true, true>::Command::CtrlMod, back.command.right.ctrlMod);
|
||||
break;
|
||||
case 3:
|
||||
send(MotorController<false, false>::Command::IMotMax, controllers.front.command.left.iMotMax);
|
||||
send(MotorController<false, true>::Command::IMotMax, controllers.front.command.right.iMotMax);
|
||||
send(MotorController<true, false>::Command::IMotMax, controllers.back.command.left.iMotMax);
|
||||
send(MotorController<true, true>::Command::IMotMax, controllers.back.command.right.iMotMax);
|
||||
send(MotorController<false, false>::Command::IMotMax, front.command.left.iMotMax);
|
||||
send(MotorController<false, true>::Command::IMotMax, front.command.right.iMotMax);
|
||||
send(MotorController<true, false>::Command::IMotMax, back.command.left.iMotMax);
|
||||
send(MotorController<true, true>::Command::IMotMax, back.command.right.iMotMax);
|
||||
break;
|
||||
case 4:
|
||||
send(MotorController<false, false>::Command::IDcMax, controllers.front.command.left.iDcMax);
|
||||
send(MotorController<false, true>::Command::IDcMax, controllers.front.command.right.iDcMax);
|
||||
send(MotorController<true, false>::Command::IDcMax, controllers.back.command.left.iDcMax);
|
||||
send(MotorController<true, true>::Command::IDcMax, controllers.back.command.right.iDcMax);
|
||||
send(MotorController<false, false>::Command::IDcMax, front.command.left.iDcMax);
|
||||
send(MotorController<false, true>::Command::IDcMax, front.command.right.iDcMax);
|
||||
send(MotorController<true, false>::Command::IDcMax, back.command.left.iDcMax);
|
||||
send(MotorController<true, true>::Command::IDcMax, back.command.right.iDcMax);
|
||||
break;
|
||||
case 5:
|
||||
send(MotorController<false, false>::Command::NMotMax, controllers.front.command.left.nMotMax);
|
||||
send(MotorController<false, true>::Command::NMotMax, controllers.front.command.right.nMotMax);
|
||||
send(MotorController<true, false>::Command::NMotMax, controllers.back.command.left.nMotMax);
|
||||
send(MotorController<true, true>::Command::NMotMax, controllers.back.command.right.nMotMax);
|
||||
send(MotorController<false, false>::Command::NMotMax, front.command.left.nMotMax);
|
||||
send(MotorController<false, true>::Command::NMotMax, front.command.right.nMotMax);
|
||||
send(MotorController<true, false>::Command::NMotMax, back.command.left.nMotMax);
|
||||
send(MotorController<true, true>::Command::NMotMax, back.command.right.nMotMax);
|
||||
break;
|
||||
case 6:
|
||||
send(MotorController<false, false>::Command::FieldWeakMax, controllers.front.command.left.fieldWeakMax);
|
||||
send(MotorController<false, true>::Command::FieldWeakMax, controllers.front.command.right.fieldWeakMax);
|
||||
send(MotorController<true, false>::Command::FieldWeakMax, controllers.back.command.left.fieldWeakMax);
|
||||
send(MotorController<true, true>::Command::FieldWeakMax, controllers.back.command.right.fieldWeakMax);
|
||||
send(MotorController<false, false>::Command::FieldWeakMax, front.command.left.fieldWeakMax);
|
||||
send(MotorController<false, true>::Command::FieldWeakMax, front.command.right.fieldWeakMax);
|
||||
send(MotorController<true, false>::Command::FieldWeakMax, back.command.left.fieldWeakMax);
|
||||
send(MotorController<true, true>::Command::FieldWeakMax, back.command.right.fieldWeakMax);
|
||||
break;
|
||||
case 7:
|
||||
send(MotorController<false, false>::Command::PhaseAdvMax, controllers.front.command.left.phaseAdvMax);
|
||||
send(MotorController<false, true>::Command::PhaseAdvMax, controllers.front.command.right.phaseAdvMax);
|
||||
send(MotorController<true, false>::Command::PhaseAdvMax, controllers.back.command.left.phaseAdvMax);
|
||||
send(MotorController<true, true>::Command::PhaseAdvMax, controllers.back.command.right.phaseAdvMax);
|
||||
send(MotorController<false, false>::Command::PhaseAdvMax, front.command.left.phaseAdvMax);
|
||||
send(MotorController<false, true>::Command::PhaseAdvMax, front.command.right.phaseAdvMax);
|
||||
send(MotorController<true, false>::Command::PhaseAdvMax, back.command.left.phaseAdvMax);
|
||||
send(MotorController<true, true>::Command::PhaseAdvMax, back.command.right.phaseAdvMax);
|
||||
break;
|
||||
case 8:
|
||||
send(MotorController<false, false>::Command::BuzzerFreq, controllers.front.command.buzzer.freq);
|
||||
send(MotorController<false, true>::Command::BuzzerFreq, controllers.front.command.buzzer.freq);
|
||||
send(MotorController<true, false>::Command::BuzzerFreq, controllers.back.command.buzzer.freq);
|
||||
send(MotorController<true, true>::Command::BuzzerFreq, controllers.back.command.buzzer.freq);
|
||||
if (send(MotorController<false, false>::Command::BuzzerFreq, front.command.buzzer.freq) == ESP_OK)
|
||||
lastValues.front.freq = front.command.buzzer.freq;
|
||||
// if (send(MotorController<false, true>::Command::BuzzerFreq, front.command.buzzer.freq) == ESP_OK)
|
||||
// lastValues.front.freq = front.command.buzzer.freq;
|
||||
if (send(MotorController<true, false>::Command::BuzzerFreq, back.command.buzzer.freq) == ESP_OK)
|
||||
lastValues.back.freq = back.command.buzzer.freq;
|
||||
// if (send(MotorController<true, true>::Command::BuzzerFreq, back.command.buzzer.freq) == ESP_OK)
|
||||
// lastValues.back.freq = back.command.buzzer.freq;
|
||||
if (send(MotorController<false, false>::Command::BuzzerPattern, front.command.buzzer.pattern) == ESP_OK)
|
||||
lastValues.front.pattern = front.command.buzzer.pattern;
|
||||
// if (send(MotorController<false, true>::Command::BuzzerPattern, front.command.buzzer.pattern) == ESP_OK)
|
||||
// lastValues.front.pattern = front.command.buzzer.pattern;
|
||||
if (send(MotorController<true, false>::Command::BuzzerPattern, back.command.buzzer.pattern) == ESP_OK)
|
||||
lastValues.back.pattern = back.command.buzzer.pattern;
|
||||
// if (send(MotorController<true, true>::Command::BuzzerPattern, back.command.buzzer.pattern) == ESP_OK)
|
||||
// lastValues.back.pattern = back.command.buzzer.pattern;
|
||||
break;
|
||||
case 9:
|
||||
send(MotorController<false, false>::Command::BuzzerPattern, controllers.front.command.buzzer.pattern);
|
||||
send(MotorController<false, true>::Command::BuzzerPattern, controllers.front.command.buzzer.pattern);
|
||||
send(MotorController<true, false>::Command::BuzzerPattern, controllers.back.command.buzzer.pattern);
|
||||
send(MotorController<true, true>::Command::BuzzerPattern, controllers.back.command.buzzer.pattern);
|
||||
send(MotorController<false, false>::Command::Led, front.command.led);
|
||||
//send(MotorController<false, true>::Command::Led, front.command.led);
|
||||
send(MotorController<true, false>::Command::Led, back.command.led);
|
||||
//send(MotorController<true, true>::Command::Led, back.command.led);
|
||||
send(MotorController<false, false>::Command::Poweroff, front.command.poweroff);
|
||||
//send(MotorController<false, true>::Command::Poweroff, front.command.poweroff);
|
||||
send(MotorController<true, false>::Command::Poweroff, back.command.poweroff);
|
||||
//send(MotorController<true, true>::Command::Poweroff, back.command.poweroff);
|
||||
break;
|
||||
case 10:
|
||||
send(MotorController<false, false>::Command::Led, controllers.front.command.led);
|
||||
send(MotorController<false, true>::Command::Led, controllers.front.command.led);
|
||||
send(MotorController<true, false>::Command::Led, controllers.back.command.led);
|
||||
send(MotorController<true, true>::Command::Led, controllers.back.command.led);
|
||||
break;
|
||||
case 11:
|
||||
send(MotorController<false, false>::Command::Poweroff, controllers.front.command.poweroff);
|
||||
send(MotorController<false, true>::Command::Poweroff, controllers.front.command.poweroff);
|
||||
send(MotorController<true, false>::Command::Poweroff, controllers.back.command.poweroff);
|
||||
send(MotorController<true, true>::Command::Poweroff, controllers.back.command.poweroff);
|
||||
if (send(Boardcomputer::Feedback::ButtonLeds, buttonLeds) == ESP_OK)
|
||||
lastValues.buttonLeds = buttonLeds;
|
||||
default:
|
||||
i=0;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
} // namespace
|
||||
} // namespace can
|
||||
|
@ -79,7 +79,7 @@ private:
|
||||
|
||||
Status m_status;
|
||||
int16_t m_gasMin, m_gasMax, m_bremsMin, m_bremsMax;
|
||||
float m_gas, m_brems;
|
||||
std::optional<float> m_gas, m_brems;
|
||||
};
|
||||
|
||||
CalibrateDisplay::CalibrateDisplay(bool bootup) :
|
||||
@ -94,8 +94,8 @@ void CalibrateDisplay::start()
|
||||
m_selectedButton = 0;
|
||||
m_status = Status::Begin;
|
||||
copyFromSettings();
|
||||
m_gas = 0.f;
|
||||
m_brems = 0.f;
|
||||
m_gas = std::nullopt;
|
||||
m_brems = std::nullopt;
|
||||
}
|
||||
|
||||
void CalibrateDisplay::initScreen()
|
||||
@ -124,14 +124,21 @@ void CalibrateDisplay::initScreen()
|
||||
|
||||
void CalibrateDisplay::update()
|
||||
{
|
||||
m_gas = scaleBetween<float>(raw_gas, m_gasMin, m_gasMax, 0., 1000.);
|
||||
m_brems = scaleBetween<float>(raw_brems, m_bremsMin, m_bremsMax, 0., 1000.);
|
||||
if (raw_gas)
|
||||
m_gas = scaleBetween<float>(*raw_gas, m_gasMin, m_gasMax, 0., 1000.);
|
||||
else
|
||||
m_gas = std::nullopt;
|
||||
|
||||
if (raw_brems)
|
||||
m_brems = scaleBetween<float>(*raw_brems, m_bremsMin, m_bremsMax, 0., 1000.);
|
||||
else
|
||||
m_brems = std::nullopt;
|
||||
}
|
||||
|
||||
void CalibrateDisplay::redraw()
|
||||
{
|
||||
m_labels[0].redraw(std::to_string(m_gas));
|
||||
m_labels[1].redraw(std::to_string(raw_gas));
|
||||
m_labels[0].redraw(m_gas ? std::to_string(*m_gas) : "?");
|
||||
m_labels[1].redraw(raw_gas ? std::to_string(*raw_gas) : "?");
|
||||
if (m_status == Status::GasMin)
|
||||
tft.setTextColor(TFT_RED, TFT_BLACK);
|
||||
m_labels[2].redraw(std::to_string(m_gasMin));
|
||||
@ -143,10 +150,10 @@ void CalibrateDisplay::redraw()
|
||||
if (m_status == Status::GasMax)
|
||||
tft.setTextColor(TFT_WHITE, TFT_BLACK);
|
||||
|
||||
m_progressBars[0].redraw(m_gas);
|
||||
m_progressBars[0].redraw(m_gas ? *m_gas : 0);
|
||||
|
||||
m_labels[4].redraw(std::to_string(m_brems));
|
||||
m_labels[5].redraw(std::to_string(raw_brems));
|
||||
m_labels[4].redraw(m_brems ? std::to_string(*m_brems) : "?");
|
||||
m_labels[5].redraw(raw_brems ? std::to_string(*raw_brems) : "?");
|
||||
if (m_status == Status::BremsMin)
|
||||
tft.setTextColor(TFT_RED, TFT_BLACK);
|
||||
m_labels[6].redraw(std::to_string(m_bremsMin));
|
||||
@ -158,7 +165,7 @@ void CalibrateDisplay::redraw()
|
||||
if (m_status == Status::BremsMax)
|
||||
tft.setTextColor(TFT_WHITE, TFT_BLACK);
|
||||
|
||||
m_progressBars[1].redraw(m_brems);
|
||||
m_progressBars[1].redraw(m_brems ? *m_brems : 0);
|
||||
|
||||
m_labels[8].redraw([&](){
|
||||
switch (m_status)
|
||||
@ -174,7 +181,8 @@ void CalibrateDisplay::redraw()
|
||||
}());
|
||||
|
||||
{
|
||||
const auto color = m_status == Status::Confirm && (m_gas > 100 || m_brems > 100) ? TFT_DARKGREY : TFT_WHITE;
|
||||
const auto failed = !m_gas || !m_brems || (m_status == Status::Confirm && (*m_gas > 100 || *m_brems > 100));
|
||||
const auto color = failed ? TFT_DARKGREY : TFT_WHITE;
|
||||
tft.setTextColor(color, TFT_BLACK);
|
||||
m_labels[9].redraw([&](){
|
||||
switch (m_status)
|
||||
@ -255,17 +263,20 @@ void CalibrateDisplay::confirm()
|
||||
switch (m_selectedButton)
|
||||
{
|
||||
case 0: // left button pressed
|
||||
if (!raw_gas || !raw_brems || !m_gas || !m_brems)
|
||||
return;
|
||||
|
||||
switch (m_status)
|
||||
{
|
||||
case Status::Begin:
|
||||
m_status = Status::GasMin;
|
||||
break;
|
||||
case Status::GasMin:
|
||||
m_gasMin = raw_gas;
|
||||
m_gasMin = *raw_gas;
|
||||
m_status = Status::GasMax;
|
||||
break;
|
||||
case Status::GasMax:
|
||||
m_gasMax = raw_gas;
|
||||
m_gasMax = *raw_gas;
|
||||
m_status = Status::BremsMin;
|
||||
{
|
||||
const auto dead = (m_gasMax - m_gasMin)/20;
|
||||
@ -274,11 +285,11 @@ void CalibrateDisplay::confirm()
|
||||
}
|
||||
break;
|
||||
case Status::BremsMin:
|
||||
m_bremsMin = raw_brems;
|
||||
m_bremsMin = *raw_brems;
|
||||
m_status = Status::BremsMax;
|
||||
break;
|
||||
case Status::BremsMax:
|
||||
m_bremsMax = raw_brems;
|
||||
m_bremsMax = *raw_brems;
|
||||
m_status = Status::Confirm;
|
||||
{
|
||||
const auto dead = (m_bremsMax - m_bremsMin)/20;
|
||||
@ -287,7 +298,7 @@ void CalibrateDisplay::confirm()
|
||||
}
|
||||
break;
|
||||
case Status::Confirm:
|
||||
if (m_gas > 100 || m_brems > 100)
|
||||
if (*m_gas > 100 || *m_brems > 100)
|
||||
return;
|
||||
copyToSettings();
|
||||
saveSettings();
|
||||
|
@ -83,8 +83,8 @@ void DPad5WireDebugDisplay::redraw()
|
||||
m_labelProfile1.redraw(std::get<DPAD_5WIRESW_PROFILE1>(dpad5wire::lastState) ? "1" : "0");
|
||||
m_labelProfile2.redraw(std::get<DPAD_5WIRESW_PROFILE2>(dpad5wire::lastState) ? "1" : "0");
|
||||
m_labelProfile3.redraw(std::get<DPAD_5WIRESW_PROFILE3>(dpad5wire::lastState) ? "1" : "0");
|
||||
m_labelGas.redraw(std::to_string(raw_gas));
|
||||
m_labelBrems.redraw(std::to_string(raw_brems));
|
||||
m_labelGas.redraw(raw_gas ? std::to_string(*raw_gas) : "?");
|
||||
m_labelBrems.redraw(raw_brems ? std::to_string(*raw_brems) : "?");
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
@ -24,11 +24,23 @@ class SettingsMenu;
|
||||
namespace {
|
||||
struct GasText : public virtual TextInterface {
|
||||
public:
|
||||
std::string text() const override { return std::string{"gas: "} + std::to_string(raw_gas) + ": " + std::to_string(gas); }
|
||||
std::string text() const override
|
||||
{
|
||||
return std::string{"gas: "} +
|
||||
(raw_gas ? std::to_string(*raw_gas) : "?") +
|
||||
": " +
|
||||
(gas ? std::to_string(*gas) : "?");
|
||||
}
|
||||
};
|
||||
struct BremsText : public virtual TextInterface {
|
||||
public:
|
||||
std::string text() const override { return std::string{"brems: "} + std::to_string(raw_brems) + ": " + std::to_string(brems); }
|
||||
std::string text() const override
|
||||
{
|
||||
return std::string{"brems: "} +
|
||||
(raw_brems ? std::to_string(*raw_brems) : "?") +
|
||||
": " +
|
||||
(brems ? std::to_string(*brems) : "?");
|
||||
}
|
||||
};
|
||||
|
||||
using SampleCountChangeScreen = makeComponent<
|
||||
|
@ -60,9 +60,7 @@ public:
|
||||
constructMenuItem<makeComponent<MenuItem, StaticText<TEXT_WHEELDIAMETERMM>, SwitchScreenAction<WheelDiameterMmChangeScreen>>>();
|
||||
constructMenuItem<makeComponent<MenuItem, StaticText<TEXT_WHEELDIAMETERINCH>, SwitchScreenAction<WheelDiameterInchChangeScreen>>>();
|
||||
constructMenuItem<makeComponent<MenuItem, StaticText<TEXT_NUMMAGNETPOLES>, SwitchScreenAction<NumMagnetPolesChangeScreen>>>();
|
||||
#ifdef FEATURE_SERIAL
|
||||
constructMenuItem<makeComponent<MenuItem, StaticText<TEXT_SWAPFRONTBACK>, ToggleBoolAction, CheckboxIcon, SwapFrontBackAccessor>>();
|
||||
#endif
|
||||
constructMenuItem<makeComponent<MenuItem, StaticText<TEXT_BACK>, SwitchScreenAction<SettingsMenu>, StaticMenuItemIcon<&icons::back>>>();
|
||||
}
|
||||
};
|
||||
|
@ -145,12 +145,12 @@ void StatusDisplay::initScreen()
|
||||
void StatusDisplay::redraw()
|
||||
{
|
||||
tft.setTextFont(2);
|
||||
m_labelRawGas.redraw(std::to_string(raw_gas));
|
||||
m_labelGas.redraw(std::to_string(gas));
|
||||
m_progressBarGas.redraw(gas);
|
||||
m_labelRawBrems.redraw(std::to_string(raw_brems));
|
||||
m_labelBrems.redraw(std::to_string(brems));
|
||||
m_progressBarBrems.redraw(brems);
|
||||
m_labelRawGas.redraw(raw_gas ? std::to_string(*raw_gas) : "?");
|
||||
m_labelGas.redraw(gas ? std::to_string(*gas) : "?");
|
||||
m_progressBarGas.redraw(gas ? *gas : 0);
|
||||
m_labelRawBrems.redraw(raw_brems ? std::to_string(*raw_brems) : "?");
|
||||
m_labelBrems.redraw(brems ? std::to_string(*brems) : "?");
|
||||
m_progressBarBrems.redraw(brems ? *brems : 0);
|
||||
|
||||
m_frontStatus.redraw(controllers.front);
|
||||
m_backStatus.redraw(controllers.back);
|
||||
|
@ -4,8 +4,8 @@
|
||||
|
||||
#include <Arduino.h>
|
||||
|
||||
#include "globals.h"
|
||||
#include "types.h"
|
||||
#include "buttons.h"
|
||||
|
||||
namespace {
|
||||
namespace dpad
|
||||
|
@ -2,11 +2,9 @@
|
||||
|
||||
#include <Arduino.h>
|
||||
|
||||
#include "globals.h"
|
||||
|
||||
#include "dpad.h"
|
||||
#include "globals.h"
|
||||
#include "types.h"
|
||||
#include "buttons.h"
|
||||
|
||||
namespace {
|
||||
namespace dpad3wire
|
||||
|
118
src/dpad5wire.h
118
src/dpad5wire.h
@ -1,17 +1,42 @@
|
||||
#pragma once
|
||||
|
||||
#include <tuple>
|
||||
#include <array>
|
||||
|
||||
#include <Arduino.h>
|
||||
|
||||
#include "globals.h"
|
||||
#include "types.h"
|
||||
#include "actions/switchprofileaction.h"
|
||||
#include "buttons.h"
|
||||
|
||||
namespace {
|
||||
namespace dpad5wire
|
||||
{
|
||||
using State = std::tuple<bool, bool, bool, bool, bool, bool, bool, bool>;
|
||||
class State : public std::array<bool, 8>
|
||||
{
|
||||
public:
|
||||
State() : std::array<bool, 8>{false, false, false, false, false, false, false, false} {}
|
||||
State(const std::array<bool, 8> &other) : std::array<bool, 8>{} {}
|
||||
|
||||
State &operator=(const std::array<bool, 8> &other)
|
||||
{
|
||||
std::array<bool, 8>::operator=(other);
|
||||
return *this;
|
||||
}
|
||||
|
||||
State &operator=(const State &other)
|
||||
{
|
||||
std::array<bool, 8>::operator=(other);
|
||||
return *this;
|
||||
}
|
||||
|
||||
bool &up{this->at(DPAD_5WIRESW_UP)};
|
||||
bool &down{this->at(DPAD_5WIRESW_DOWN)};
|
||||
bool &confirm{this->at(DPAD_5WIRESW_CONFIRM)};
|
||||
bool &back{this->at(DPAD_5WIRESW_BACK)};
|
||||
bool &profile0{this->at(DPAD_5WIRESW_PROFILE0)};
|
||||
bool &profile1{this->at(DPAD_5WIRESW_PROFILE1)};
|
||||
bool &profile2{this->at(DPAD_5WIRESW_PROFILE2)};
|
||||
bool &profile3{this->at(DPAD_5WIRESW_PROFILE3)};
|
||||
};
|
||||
|
||||
template<pin_t OUT, pin_t IN1, pin_t IN2, pin_t IN3, pin_t IN4>
|
||||
class Helper
|
||||
@ -37,6 +62,8 @@ void Helper<OUT, IN1, IN2, IN3, IN4>::begin()
|
||||
template<pin_t OUT, pin_t IN1, pin_t IN2, pin_t IN3, pin_t IN4>
|
||||
State Helper<OUT, IN1, IN2, IN3, IN4>::read()
|
||||
{
|
||||
State result;
|
||||
|
||||
digitalWrite(OUT, LOW);
|
||||
|
||||
pinMode(IN1, INPUT_PULLUP);
|
||||
@ -46,10 +73,10 @@ State Helper<OUT, IN1, IN2, IN3, IN4>::read()
|
||||
|
||||
delay(1);
|
||||
|
||||
const bool result0 = digitalRead(IN1)==LOW;
|
||||
const bool result1 = digitalRead(IN2)==LOW;
|
||||
const bool result2 = digitalRead(IN3)==LOW;
|
||||
const bool result3 = digitalRead(IN4)==LOW;
|
||||
result[0] = digitalRead(IN1)==LOW;
|
||||
result[1] = digitalRead(IN2)==LOW;
|
||||
result[2] = digitalRead(IN3)==LOW;
|
||||
result[3] = digitalRead(IN4)==LOW;
|
||||
|
||||
digitalWrite(OUT, HIGH);
|
||||
|
||||
@ -60,12 +87,12 @@ State Helper<OUT, IN1, IN2, IN3, IN4>::read()
|
||||
|
||||
delay(1);
|
||||
|
||||
const bool result4 = digitalRead(IN1);
|
||||
const bool result5 = digitalRead(IN2);
|
||||
const bool result6 = digitalRead(IN3);
|
||||
const bool result7 = digitalRead(IN4);
|
||||
result[4] = digitalRead(IN1);
|
||||
result[5] = digitalRead(IN2);
|
||||
result[6] = digitalRead(IN3);
|
||||
result[7] = digitalRead(IN4);
|
||||
|
||||
return std::make_tuple(result0, result1, result2, result3, result4, result5, result6, result7);
|
||||
return result;
|
||||
}
|
||||
|
||||
#ifdef FEATURE_DPAD_5WIRESW
|
||||
@ -81,77 +108,66 @@ void init()
|
||||
|
||||
void update()
|
||||
{
|
||||
const auto state = helper.read();
|
||||
const auto newState = helper.read();
|
||||
|
||||
#ifdef DPAD_5WIRESW_DEBUG
|
||||
lastState = state;
|
||||
lastState = newState;
|
||||
return;
|
||||
#endif
|
||||
|
||||
const auto now = millis();
|
||||
|
||||
if (std::get<DPAD_5WIRESW_UP>(lastState) != std::get<DPAD_5WIRESW_UP>(state) && now-debounceUp > settings.boardcomputerHardware.dpadDebounce)
|
||||
if (lastState.up != newState.up && now-debounceUp > settings.boardcomputerHardware.dpadDebounce)
|
||||
{
|
||||
if (std::get<DPAD_5WIRESW_UP>(state))
|
||||
if (newState.up)
|
||||
InputDispatcher::rotate(-1);
|
||||
std::get<DPAD_5WIRESW_UP>(lastState) = std::get<DPAD_5WIRESW_UP>(state);
|
||||
debounceUp = now;
|
||||
}
|
||||
if (std::get<DPAD_5WIRESW_DOWN>(lastState) != std::get<DPAD_5WIRESW_DOWN>(state) && now-debounceDown > settings.boardcomputerHardware.dpadDebounce)
|
||||
|
||||
if (lastState.down != newState.down && now-debounceDown > settings.boardcomputerHardware.dpadDebounce)
|
||||
{
|
||||
if (std::get<DPAD_5WIRESW_DOWN>(state))
|
||||
if (newState.down)
|
||||
InputDispatcher::rotate(1);
|
||||
std::get<DPAD_5WIRESW_DOWN>(lastState) = std::get<DPAD_5WIRESW_DOWN>(state);
|
||||
debounceDown = now;
|
||||
}
|
||||
if (std::get<DPAD_5WIRESW_CONFIRM>(lastState) != std::get<DPAD_5WIRESW_CONFIRM>(state) && now-debounceConfirm > settings.boardcomputerHardware.dpadDebounce)
|
||||
|
||||
if (lastState.confirm != newState.confirm && now-debounceConfirm > settings.boardcomputerHardware.dpadDebounce)
|
||||
{
|
||||
InputDispatcher::confirmButton(std::get<DPAD_5WIRESW_CONFIRM>(state));
|
||||
std::get<DPAD_5WIRESW_CONFIRM>(lastState) = std::get<DPAD_5WIRESW_CONFIRM>(state);
|
||||
InputDispatcher::confirmButton(std::get<DPAD_5WIRESW_CONFIRM>(newState));
|
||||
debounceConfirm = now;
|
||||
}
|
||||
if (std::get<DPAD_5WIRESW_BACK>(lastState) != std::get<DPAD_5WIRESW_BACK>(state) && now-debounceBack > settings.boardcomputerHardware.dpadDebounce)
|
||||
|
||||
if (lastState.back != newState.back && now-debounceBack > settings.boardcomputerHardware.dpadDebounce)
|
||||
{
|
||||
InputDispatcher::backButton(std::get<DPAD_5WIRESW_BACK>(state));
|
||||
std::get<DPAD_5WIRESW_BACK>(lastState) = std::get<DPAD_5WIRESW_BACK>(state);
|
||||
InputDispatcher::backButton(std::get<DPAD_5WIRESW_BACK>(newState));
|
||||
debounceBack = now;
|
||||
}
|
||||
if (std::get<DPAD_5WIRESW_PROFILE0>(lastState) != std::get<DPAD_5WIRESW_PROFILE0>(state) && now-debounceProfile0 > settings.boardcomputerHardware.dpadDebounce)
|
||||
|
||||
if (lastState.profile0 != newState.profile0 && now-debounceProfile0 > settings.boardcomputerHardware.dpadDebounce)
|
||||
{
|
||||
if (std::get<DPAD_5WIRESW_PROFILE0>(state))
|
||||
{
|
||||
SwitchProfileAction<0>{}.triggered();
|
||||
}
|
||||
std::get<DPAD_5WIRESW_PROFILE0>(lastState) = std::get<DPAD_5WIRESW_PROFILE0>(state);
|
||||
InputDispatcher::profileButton(0, std::get<DPAD_5WIRESW_PROFILE0>(newState));
|
||||
debounceProfile0 = now;
|
||||
}
|
||||
if (std::get<DPAD_5WIRESW_PROFILE1>(lastState) != std::get<DPAD_5WIRESW_PROFILE1>(state) && now-debounceProfile1 > settings.boardcomputerHardware.dpadDebounce)
|
||||
|
||||
if (lastState.profile1 != newState.profile1 && now-debounceProfile1 > settings.boardcomputerHardware.dpadDebounce)
|
||||
{
|
||||
if (std::get<DPAD_5WIRESW_PROFILE1>(state))
|
||||
{
|
||||
SwitchProfileAction<1>{}.triggered();
|
||||
}
|
||||
std::get<DPAD_5WIRESW_PROFILE1>(lastState) = std::get<DPAD_5WIRESW_PROFILE1>(state);
|
||||
InputDispatcher::profileButton(1, std::get<DPAD_5WIRESW_PROFILE1>(newState));
|
||||
debounceProfile1 = now;
|
||||
}
|
||||
if (std::get<DPAD_5WIRESW_PROFILE2>(lastState) != std::get<DPAD_5WIRESW_PROFILE2>(state) && now-debounceProfile2 > settings.boardcomputerHardware.dpadDebounce)
|
||||
|
||||
if (lastState.profile2 != newState.profile2 && now-debounceProfile2 > settings.boardcomputerHardware.dpadDebounce)
|
||||
{
|
||||
if (std::get<DPAD_5WIRESW_PROFILE2>(state))
|
||||
{
|
||||
SwitchProfileAction<2>{}.triggered();
|
||||
}
|
||||
std::get<DPAD_5WIRESW_PROFILE2>(lastState) = std::get<DPAD_5WIRESW_PROFILE2>(state);
|
||||
InputDispatcher::profileButton(2, std::get<DPAD_5WIRESW_PROFILE2>(newState));
|
||||
debounceProfile2 = now;
|
||||
}
|
||||
if (std::get<DPAD_5WIRESW_PROFILE3>(lastState) != std::get<DPAD_5WIRESW_PROFILE3>(state) && now-debounceProfile3 > settings.boardcomputerHardware.dpadDebounce)
|
||||
|
||||
if (lastState.profile3 != newState.profile3 && now-debounceProfile3 > settings.boardcomputerHardware.dpadDebounce)
|
||||
{
|
||||
if (std::get<DPAD_5WIRESW_PROFILE3>(state))
|
||||
{
|
||||
SwitchProfileAction<3>{}.triggered();
|
||||
}
|
||||
std::get<DPAD_5WIRESW_PROFILE3>(lastState) = std::get<DPAD_5WIRESW_PROFILE3>(state);
|
||||
InputDispatcher::profileButton(3, std::get<DPAD_5WIRESW_PROFILE3>(newState));
|
||||
debounceProfile3 = now;
|
||||
}
|
||||
|
||||
lastState = newState;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
@ -3,6 +3,7 @@
|
||||
// system includes
|
||||
#include <array>
|
||||
#include <memory>
|
||||
#include <optional>
|
||||
|
||||
// Arduino includes
|
||||
#ifdef FEATURE_BLUETOOTH
|
||||
@ -21,8 +22,9 @@
|
||||
#include "types.h"
|
||||
|
||||
namespace {
|
||||
int16_t raw_gas, raw_brems;
|
||||
float gas, brems;
|
||||
std::optional<int16_t> raw_gas, raw_brems;
|
||||
std::optional<float> gas, brems;
|
||||
|
||||
#ifdef FEATURE_GAMETRAK
|
||||
int16_t raw_gametrakX, raw_gametrakY, raw_gametrakDist;
|
||||
float gametrakX, gametrakY, gametrakDist;
|
||||
@ -82,64 +84,4 @@ TFT_eSPI tft = TFT_eSPI();
|
||||
ModeInterface *currentMode{};
|
||||
|
||||
std::unique_ptr<Display> currentDisplay;
|
||||
|
||||
int rotated{};
|
||||
bool requestFullRedraw{};
|
||||
bool confirmButtonPressed{};
|
||||
bool confirmButtonLongPressed{};
|
||||
bool backButtonPressed{};
|
||||
bool backButtonLongPressed{};
|
||||
|
||||
class InputDispatcher
|
||||
{
|
||||
public:
|
||||
static void rotate(int offset)
|
||||
{
|
||||
rotated += offset;
|
||||
}
|
||||
|
||||
static void confirmButton(bool pressed)
|
||||
{
|
||||
static millis_t pressBegin = 0;
|
||||
|
||||
const auto now = millis();
|
||||
|
||||
if (pressed)
|
||||
pressBegin = now;
|
||||
else
|
||||
{
|
||||
const auto duration = now - pressBegin;
|
||||
|
||||
if (duration < 500)
|
||||
confirmButtonPressed = true;
|
||||
else if (duration < 2000)
|
||||
confirmButtonLongPressed = true;
|
||||
else
|
||||
requestFullRedraw = true;
|
||||
|
||||
pressBegin = 0;
|
||||
}
|
||||
}
|
||||
|
||||
static void backButton(bool pressed)
|
||||
{
|
||||
static millis_t pressBegin = 0;
|
||||
|
||||
const auto now = millis();
|
||||
|
||||
if (pressed)
|
||||
pressBegin = now;
|
||||
else
|
||||
{
|
||||
const auto duration = now - pressBegin;
|
||||
|
||||
if (duration < 500)
|
||||
backButtonPressed = true;
|
||||
else
|
||||
backButtonLongPressed = true;
|
||||
|
||||
pressBegin = 0;
|
||||
}
|
||||
}
|
||||
};
|
||||
}
|
||||
|
16
src/main.cpp
16
src/main.cpp
@ -308,7 +308,7 @@ void setup()
|
||||
#endif
|
||||
|
||||
#ifdef FEATURE_CAN
|
||||
initCan();
|
||||
can::initCan();
|
||||
#endif
|
||||
|
||||
#ifdef FEATURE_SERIAL
|
||||
@ -319,10 +319,10 @@ void setup()
|
||||
controllers.back.serial.get().begin(38400, SERIAL_8N1, PINS_RX2, PINS_TX2);
|
||||
#endif
|
||||
|
||||
raw_gas = 0;
|
||||
raw_brems = 0;
|
||||
gas = 0;
|
||||
brems = 0;
|
||||
raw_gas = std::nullopt;
|
||||
raw_brems = std::nullopt;
|
||||
gas = std::nullopt;
|
||||
brems = std::nullopt;
|
||||
|
||||
for (Controller &controller : controllers)
|
||||
controller.command.buzzer = {};
|
||||
@ -357,7 +357,7 @@ void setup()
|
||||
return;
|
||||
#endif
|
||||
|
||||
if (gas > 200.f || brems > 200.f)
|
||||
if (!gas || !brems || *gas > 200.f || *brems > 200.f)
|
||||
switchScreen<CalibrateDisplay>(true);
|
||||
else
|
||||
switchScreen<StatusDisplay>();
|
||||
@ -439,9 +439,7 @@ void loop()
|
||||
}
|
||||
|
||||
#ifdef FEATURE_CAN
|
||||
for (int i = 0; i < 4; i++)
|
||||
if (!parseCanInput())
|
||||
break;
|
||||
can::parseCanInput();
|
||||
#endif
|
||||
|
||||
#ifdef FEATURE_SERIAL
|
||||
|
@ -31,64 +31,81 @@ DefaultMode defaultMode;
|
||||
|
||||
void DefaultMode::update()
|
||||
{
|
||||
if (waitForGasLoslass)
|
||||
if (!gas || !brems)
|
||||
{
|
||||
if (gas < 50)
|
||||
waitForGasLoslass = false;
|
||||
else
|
||||
gas = 0;
|
||||
}
|
||||
start();
|
||||
|
||||
if (waitForBremsLoslass)
|
||||
{
|
||||
if (brems < 50)
|
||||
waitForBremsLoslass = false;
|
||||
else
|
||||
brems = 0;
|
||||
}
|
||||
|
||||
const auto gas_processed = settings.defaultMode.squareGas ? (gas * gas) / 1000.f : gas;
|
||||
const auto brems_processed = settings.defaultMode.squareBrems ? (brems * brems) / 1000 : brems;
|
||||
|
||||
const auto now = millis();
|
||||
|
||||
float pwm;
|
||||
if (gas_processed >= settings.defaultMode.add_schwelle)
|
||||
{
|
||||
pwm = (gas_processed/1000.*settings.defaultMode.gas1_wert) + (brems_processed/1000.*settings.defaultMode.brems1_wert);
|
||||
|
||||
if (settings.defaultMode.enableSmoothing && (pwm > 1000. || lastPwm > 1000.))
|
||||
for (bobbycar::protocol::serial::MotorState &motor : motors())
|
||||
{
|
||||
if (lastPwm < pwm)
|
||||
{
|
||||
pwm = std::min(pwm, lastPwm+(settings.defaultMode.smoothing*(now-lastTime)/100.f));
|
||||
if (pwm < 1000.)
|
||||
pwm = 1000.;
|
||||
}
|
||||
else if (lastPwm > pwm)
|
||||
{
|
||||
pwm = std::max(pwm, lastPwm-(settings.defaultMode.smoothing*(now-lastTime)/100.f));
|
||||
}
|
||||
motor.ctrlTyp = bobbycar::protocol::ControlType::FieldOrientedControl;
|
||||
motor.ctrlMod = bobbycar::protocol::ControlMode::OpenMode;
|
||||
motor.pwm = 0;
|
||||
}
|
||||
}
|
||||
else
|
||||
pwm = (gas_processed/1000.*settings.defaultMode.gas2_wert) - (brems_processed/1000.*settings.defaultMode.brems2_wert);
|
||||
|
||||
lastPwm = pwm;
|
||||
lastTime = now;
|
||||
|
||||
const auto pair = split(settings.defaultMode.modelMode);
|
||||
for (bobbycar::protocol::serial::MotorState &motor : motorsInController(controllers.front))
|
||||
{
|
||||
motor.ctrlTyp = pair.first;
|
||||
motor.ctrlMod = pair.second;
|
||||
motor.pwm = pwm / 100. * settings.defaultMode.frontPercentage;
|
||||
}
|
||||
for (bobbycar::protocol::serial::MotorState &motor : motorsInController(controllers.back))
|
||||
{
|
||||
motor.ctrlTyp = pair.first;
|
||||
motor.ctrlMod = pair.second;
|
||||
motor.pwm = pwm / 100. * settings.defaultMode.backPercentage;
|
||||
float local_gas = *gas;
|
||||
float local_brems = *brems;
|
||||
|
||||
if (waitForGasLoslass)
|
||||
{
|
||||
if (local_gas < 50)
|
||||
waitForGasLoslass = false;
|
||||
else
|
||||
local_gas = 0;
|
||||
}
|
||||
|
||||
if (waitForBremsLoslass)
|
||||
{
|
||||
if (local_brems < 50)
|
||||
waitForBremsLoslass = false;
|
||||
else
|
||||
local_brems = 0;
|
||||
}
|
||||
|
||||
const auto gas_processed = settings.defaultMode.squareGas ? (local_gas * local_gas) / 1000.f : local_gas;
|
||||
const auto brems_processed = settings.defaultMode.squareBrems ? (local_brems * local_brems) / 1000 : local_brems;
|
||||
|
||||
const auto now = millis();
|
||||
|
||||
float pwm;
|
||||
if (gas_processed >= settings.defaultMode.add_schwelle)
|
||||
{
|
||||
pwm = (gas_processed/1000.*settings.defaultMode.gas1_wert) + (brems_processed/1000.*settings.defaultMode.brems1_wert);
|
||||
|
||||
if (settings.defaultMode.enableSmoothing && (pwm > 1000. || lastPwm > 1000.))
|
||||
{
|
||||
if (lastPwm < pwm)
|
||||
{
|
||||
pwm = std::min(pwm, lastPwm+(settings.defaultMode.smoothing*(now-lastTime)/100.f));
|
||||
if (pwm < 1000.)
|
||||
pwm = 1000.;
|
||||
}
|
||||
else if (lastPwm > pwm)
|
||||
{
|
||||
pwm = std::max(pwm, lastPwm-(settings.defaultMode.smoothing*(now-lastTime)/100.f));
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
pwm = (gas_processed/1000.*settings.defaultMode.gas2_wert) - (brems_processed/1000.*settings.defaultMode.brems2_wert);
|
||||
|
||||
lastPwm = pwm;
|
||||
lastTime = now;
|
||||
|
||||
const auto pair = split(settings.defaultMode.modelMode);
|
||||
for (bobbycar::protocol::serial::MotorState &motor : motorsInController(controllers.front))
|
||||
{
|
||||
motor.ctrlTyp = pair.first;
|
||||
motor.ctrlMod = pair.second;
|
||||
motor.pwm = pwm / 100. * settings.defaultMode.frontPercentage;
|
||||
}
|
||||
for (bobbycar::protocol::serial::MotorState &motor : motorsInController(controllers.back))
|
||||
{
|
||||
motor.ctrlTyp = pair.first;
|
||||
motor.ctrlMod = pair.second;
|
||||
motor.pwm = pwm / 100. * settings.defaultMode.backPercentage;
|
||||
}
|
||||
}
|
||||
|
||||
fixCommonParams();
|
||||
|
@ -41,36 +41,50 @@ void GametrakMode::start()
|
||||
|
||||
void GametrakMode::update()
|
||||
{
|
||||
if (gas > 500. || brems > 500.)
|
||||
if (!gas || !brems)
|
||||
{
|
||||
modes::defaultMode.waitForGasLoslass = true;
|
||||
modes::defaultMode.waitForBremsLoslass = true;
|
||||
currentMode = &modes::defaultMode;
|
||||
return;
|
||||
}
|
||||
start();
|
||||
|
||||
int16_t pwm;
|
||||
if (gametrakDist < 150)
|
||||
{
|
||||
pwm = 0;
|
||||
m_flag = false;
|
||||
for (bobbycar::protocol::serial::MotorState &motor : motors())
|
||||
{
|
||||
motor.ctrlTyp = bobbycar::protocol::ControlType::FieldOrientedControl;
|
||||
motor.ctrlMod = bobbycar::protocol::ControlMode::OpenMode;
|
||||
motor.pwm = 0;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if (m_flag || gametrakDist >= 400)
|
||||
if (*gas > 500. || *brems > 500.)
|
||||
{
|
||||
m_flag = true;
|
||||
pwm = clamp<int>((gametrakDist - 400) / 2, -200, 200);
|
||||
modes::defaultMode.waitForGasLoslass = true;
|
||||
modes::defaultMode.waitForBremsLoslass = true;
|
||||
currentMode = &modes::defaultMode;
|
||||
return;
|
||||
}
|
||||
|
||||
int16_t pwm;
|
||||
if (gametrakDist < 150)
|
||||
{
|
||||
pwm = 0;
|
||||
m_flag = false;
|
||||
}
|
||||
else
|
||||
pwm = 0;
|
||||
}
|
||||
{
|
||||
if (m_flag || gametrakDist >= 400)
|
||||
{
|
||||
m_flag = true;
|
||||
pwm = clamp<int>((gametrakDist - 400) / 2, -200, 200);
|
||||
}
|
||||
else
|
||||
pwm = 0;
|
||||
}
|
||||
|
||||
for (bobbycar::protocol::serial::MotorState &motor : motors())
|
||||
{
|
||||
motor.ctrlTyp = bobbycar::protocol::ControlType::FieldOrientedControl;
|
||||
motor.ctrlMod = bobbycar::protocol::ControlMode::Speed;
|
||||
motor.pwm = pwm;
|
||||
for (bobbycar::protocol::serial::MotorState &motor : motors())
|
||||
{
|
||||
motor.ctrlTyp = bobbycar::protocol::ControlType::FieldOrientedControl;
|
||||
motor.ctrlMod = bobbycar::protocol::ControlMode::Speed;
|
||||
motor.pwm = pwm;
|
||||
}
|
||||
}
|
||||
|
||||
fixCommonParams();
|
||||
|
@ -36,72 +36,86 @@ void LarsmMode::start()
|
||||
|
||||
void LarsmMode::update()
|
||||
{
|
||||
for (uint8_t i = 0; i < settings.larsmMode.iterations; i++) // run multiple times to emulate higher refreshrate
|
||||
if (!gas || !brems)
|
||||
{
|
||||
// ####### larsm's bobby car code #######
|
||||
start();
|
||||
|
||||
// LOW-PASS FILTER (fliessender Mittelwert)
|
||||
adc1_filtered = adc1_filtered * 0.9 + gas * 0.1; // ADC1, TX, rechts, vorwaerts, blau
|
||||
adc2_filtered = adc2_filtered * 0.9 + brems * 0.1; // ADC2, RX, links, rueckwearts, gruen
|
||||
for (bobbycar::protocol::serial::MotorState &motor : motors())
|
||||
{
|
||||
motor.ctrlTyp = bobbycar::protocol::ControlType::FieldOrientedControl;
|
||||
motor.ctrlMod = bobbycar::protocol::ControlMode::OpenMode;
|
||||
motor.pwm = 0;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
for (uint8_t i = 0; i < settings.larsmMode.iterations; i++) // run multiple times to emulate higher refreshrate
|
||||
{
|
||||
// ####### larsm's bobby car code #######
|
||||
|
||||
// magic numbers die ich nicht mehr nachvollziehen kann, faehrt sich aber gut ;-)
|
||||
#define LOSLASS_BREMS_ACC 0.996f // naeher an 1 = gemaechlicher
|
||||
#define DRUECK_ACC2 (1.0f - LOSLASS_BREMS_ACC + 0.001f) // naeher an 0 = gemaechlicher
|
||||
#define DRUECK_ACC1 (1.0f - LOSLASS_BREMS_ACC + 0.001f) // naeher an 0 = gemaechlicher
|
||||
//die + 0.001f gleichen float ungenauigkeiten aus.
|
||||
// LOW-PASS FILTER (fliessender Mittelwert)
|
||||
adc1_filtered = adc1_filtered * 0.9 + *gas * 0.1; // ADC1, TX, rechts, vorwaerts, blau
|
||||
adc2_filtered = adc2_filtered * 0.9 + *brems * 0.1; // ADC2, RX, links, rueckwearts, gruen
|
||||
|
||||
#define ADC1_MIN 0
|
||||
#define ADC2_MIN 0
|
||||
#define ADC1_MAX 1000
|
||||
#define ADC2_MAX 1000
|
||||
// magic numbers die ich nicht mehr nachvollziehen kann, faehrt sich aber gut ;-)
|
||||
#define LOSLASS_BREMS_ACC 0.996f // naeher an 1 = gemaechlicher
|
||||
#define DRUECK_ACC2 (1.0f - LOSLASS_BREMS_ACC + 0.001f) // naeher an 0 = gemaechlicher
|
||||
#define DRUECK_ACC1 (1.0f - LOSLASS_BREMS_ACC + 0.001f) // naeher an 0 = gemaechlicher
|
||||
//die + 0.001f gleichen float ungenauigkeiten aus.
|
||||
|
||||
#define ADC2_DELTA (ADC2_MAX - ADC2_MIN)
|
||||
#define ADC1_DELTA (ADC1_MAX - ADC1_MIN)
|
||||
#define ADC1_MIN 0
|
||||
#define ADC2_MIN 0
|
||||
#define ADC1_MAX 1000
|
||||
#define ADC2_MAX 1000
|
||||
|
||||
#define CLAMP(x, low, high) (((x) > (high)) ? (high) : (((x) < (low)) ? (low) : (x)))
|
||||
#define ADC2_DELTA (ADC2_MAX - ADC2_MIN)
|
||||
#define ADC1_DELTA (ADC1_MAX - ADC1_MIN)
|
||||
|
||||
if (settings.larsmMode.mode == LarsmModeMode::Mode1) { // Mode 1, links: 3 kmh
|
||||
speed = (float)speed * LOSLASS_BREMS_ACC // bremsen wenn kein poti gedrueckt
|
||||
- (CLAMP(brems - ADC2_MIN, 0, ADC2_DELTA) / (ADC2_DELTA / 280.0f)) * DRUECK_ACC2 // links gedrueckt = zusatzbremsen oder rueckwaertsfahren
|
||||
+ (CLAMP(gas - ADC1_MIN, 0, ADC1_DELTA) / (ADC1_DELTA / 350.0f)) * DRUECK_ACC1; // vorwaerts gedrueckt = beschleunigen 12s: 350=3kmh
|
||||
weak = 0;
|
||||
#define CLAMP(x, low, high) (((x) > (high)) ? (high) : (((x) < (low)) ? (low) : (x)))
|
||||
|
||||
} else if (settings.larsmMode.mode == LarsmModeMode::Mode2) { // Mode 2, default: 6 kmh
|
||||
speed = (float)speed * LOSLASS_BREMS_ACC
|
||||
- (CLAMP(brems - ADC2_MIN, 0, ADC2_DELTA) / (ADC2_DELTA / 310.0f)) * DRUECK_ACC2
|
||||
+ (CLAMP(gas - ADC1_MIN, 0, ADC1_DELTA) / (ADC1_DELTA / 420.0f)) * DRUECK_ACC1; // 12s: 400=5-6kmh 450=7kmh
|
||||
weak = 0;
|
||||
if (settings.larsmMode.mode == LarsmModeMode::Mode1) { // Mode 1, links: 3 kmh
|
||||
speed = (float)speed * LOSLASS_BREMS_ACC // bremsen wenn kein poti gedrueckt
|
||||
- (CLAMP(*brems - ADC2_MIN, 0, ADC2_DELTA) / (ADC2_DELTA / 280.0f)) * DRUECK_ACC2 // links gedrueckt = zusatzbremsen oder rueckwaertsfahren
|
||||
+ (CLAMP(*gas - ADC1_MIN, 0, ADC1_DELTA) / (ADC1_DELTA / 350.0f)) * DRUECK_ACC1; // vorwaerts gedrueckt = beschleunigen 12s: 350=3kmh
|
||||
weak = 0;
|
||||
|
||||
} else if (settings.larsmMode.mode == LarsmModeMode::Mode3) { // Mode 3, rechts: 12 kmh
|
||||
speed = (float)speed * LOSLASS_BREMS_ACC
|
||||
- (CLAMP(brems - ADC2_MIN, 0, ADC2_DELTA) / (ADC2_DELTA / 340.0f)) * DRUECK_ACC2
|
||||
+ (CLAMP(gas - ADC1_MIN, 0, ADC1_DELTA) / (ADC1_DELTA / 600.0f)) * DRUECK_ACC1; // 12s: 600=12kmh
|
||||
weak = 0;
|
||||
} else if (settings.larsmMode.mode == LarsmModeMode::Mode2) { // Mode 2, default: 6 kmh
|
||||
speed = (float)speed * LOSLASS_BREMS_ACC
|
||||
- (CLAMP(*brems - ADC2_MIN, 0, ADC2_DELTA) / (ADC2_DELTA / 310.0f)) * DRUECK_ACC2
|
||||
+ (CLAMP(*gas - ADC1_MIN, 0, ADC1_DELTA) / (ADC1_DELTA / 420.0f)) * DRUECK_ACC1; // 12s: 400=5-6kmh 450=7kmh
|
||||
weak = 0;
|
||||
|
||||
} else if (settings.larsmMode.mode == LarsmModeMode::Mode4) { // Mode 4, l + r: full kmh
|
||||
// Feldschwaechung wird nur aktiviert wenn man schon sehr schnell ist. So gehts: Rechts voll druecken und warten bis man schnell ist, dann zusaetzlich links schnell voll druecken.
|
||||
if (adc2_filtered > (ADC2_MAX - 450) && speed > 800) { // field weakening at high speeds
|
||||
speed = (float)speed * LOSLASS_BREMS_ACC
|
||||
+ (CLAMP(gas - ADC1_MIN, 0, ADC1_DELTA) / (ADC1_DELTA / 1000.0f)) * DRUECK_ACC1;
|
||||
weak = weak * 0.95 + 400.0 * 0.05; // sanftes hinzuschalten des turbos, 12s: 400=29kmh
|
||||
} else { //normale fahrt ohne feldschwaechung
|
||||
speed = (float)speed * LOSLASS_BREMS_ACC
|
||||
- (CLAMP(brems - ADC2_MIN, 0, ADC2_DELTA) / (ADC2_DELTA / 340.0f)) * DRUECK_ACC2
|
||||
+ (CLAMP(gas - ADC1_MIN, 0, ADC1_DELTA) / (ADC1_DELTA / 1000.0f)) * DRUECK_ACC1; // 12s: 1000=22kmh
|
||||
weak = weak * 0.95; // sanftes abschalten des turbos
|
||||
}
|
||||
// weak should never exceed 400 or 450 MAX!!
|
||||
} else if (settings.larsmMode.mode == LarsmModeMode::Mode3) { // Mode 3, rechts: 12 kmh
|
||||
speed = (float)speed * LOSLASS_BREMS_ACC
|
||||
- (CLAMP(*brems - ADC2_MIN, 0, ADC2_DELTA) / (ADC2_DELTA / 340.0f)) * DRUECK_ACC2
|
||||
+ (CLAMP(*gas - ADC1_MIN, 0, ADC1_DELTA) / (ADC1_DELTA / 600.0f)) * DRUECK_ACC1; // 12s: 600=12kmh
|
||||
weak = 0;
|
||||
|
||||
} else if (settings.larsmMode.mode == LarsmModeMode::Mode4) { // Mode 4, l + r: full kmh
|
||||
// Feldschwaechung wird nur aktiviert wenn man schon sehr schnell ist. So gehts: Rechts voll druecken und warten bis man schnell ist, dann zusaetzlich links schnell voll druecken.
|
||||
if (adc2_filtered > (ADC2_MAX - 450) && speed > 800) { // field weakening at high speeds
|
||||
speed = (float)speed * LOSLASS_BREMS_ACC
|
||||
+ (CLAMP(*gas - ADC1_MIN, 0, ADC1_DELTA) / (ADC1_DELTA / 1000.0f)) * DRUECK_ACC1;
|
||||
weak = weak * 0.95 + 400.0 * 0.05; // sanftes hinzuschalten des turbos, 12s: 400=29kmh
|
||||
} else { //normale fahrt ohne feldschwaechung
|
||||
speed = (float)speed * LOSLASS_BREMS_ACC
|
||||
- (CLAMP(*brems - ADC2_MIN, 0, ADC2_DELTA) / (ADC2_DELTA / 340.0f)) * DRUECK_ACC2
|
||||
+ (CLAMP(*gas - ADC1_MIN, 0, ADC1_DELTA) / (ADC1_DELTA / 1000.0f)) * DRUECK_ACC1; // 12s: 1000=22kmh
|
||||
weak = weak * 0.95; // sanftes abschalten des turbos
|
||||
}
|
||||
// weak should never exceed 400 or 450 MAX!!
|
||||
}
|
||||
|
||||
speed = CLAMP(speed, -1000, 1000); // clamp output
|
||||
}
|
||||
|
||||
speed = CLAMP(speed, -1000, 1000); // clamp output
|
||||
}
|
||||
|
||||
for (bobbycar::protocol::serial::MotorState &motor : motors())
|
||||
{
|
||||
const auto pair = split(settings.larsmMode.modelMode);
|
||||
motor.ctrlTyp = pair.first;
|
||||
motor.ctrlMod = pair.second;
|
||||
motor.pwm = speed + weak;
|
||||
for (bobbycar::protocol::serial::MotorState &motor : motors())
|
||||
{
|
||||
const auto pair = split(settings.larsmMode.modelMode);
|
||||
motor.ctrlTyp = pair.first;
|
||||
motor.ctrlMod = pair.second;
|
||||
motor.pwm = speed + weak;
|
||||
}
|
||||
}
|
||||
|
||||
fixCommonParams();
|
||||
|
@ -32,23 +32,37 @@ void TempomatMode::start()
|
||||
|
||||
void TempomatMode::update()
|
||||
{
|
||||
if (gas > 500. && brems > 500.)
|
||||
if (!gas || !brems)
|
||||
{
|
||||
pwm = 0;
|
||||
modes::defaultMode.waitForGasLoslass = true;
|
||||
modes::defaultMode.waitForBremsLoslass = true;
|
||||
currentMode = &modes::defaultMode;
|
||||
return;
|
||||
start();
|
||||
|
||||
for (bobbycar::protocol::serial::MotorState &motor : motors())
|
||||
{
|
||||
motor.ctrlTyp = bobbycar::protocol::ControlType::FieldOrientedControl;
|
||||
motor.ctrlMod = bobbycar::protocol::ControlMode::OpenMode;
|
||||
motor.pwm = 0;
|
||||
}
|
||||
}
|
||||
|
||||
pwm += (gas/1000.) - (brems/1000.);
|
||||
|
||||
for (bobbycar::protocol::serial::MotorState &motor : motors())
|
||||
else
|
||||
{
|
||||
const auto pair = split(settings.tempomatMode.modelMode);
|
||||
motor.ctrlTyp = pair.first;
|
||||
motor.ctrlMod = pair.second;
|
||||
motor.pwm = pwm;
|
||||
if (*gas > 500. && *brems > 500.)
|
||||
{
|
||||
pwm = 0;
|
||||
modes::defaultMode.waitForGasLoslass = true;
|
||||
modes::defaultMode.waitForBremsLoslass = true;
|
||||
currentMode = &modes::defaultMode;
|
||||
return;
|
||||
}
|
||||
|
||||
pwm += (*gas/1000.) - (*brems/1000.);
|
||||
|
||||
for (bobbycar::protocol::serial::MotorState &motor : motors())
|
||||
{
|
||||
const auto pair = split(settings.tempomatMode.modelMode);
|
||||
motor.ctrlTyp = pair.first;
|
||||
motor.ctrlMod = pair.second;
|
||||
motor.pwm = pwm;
|
||||
}
|
||||
}
|
||||
|
||||
fixCommonParams();
|
||||
|
@ -32,9 +32,7 @@ constexpr Settings::ControllerHardware defaultControllerHardware {
|
||||
|
||||
.wheelDiameter = DEFAULT_WHEELDIAMETER,
|
||||
.numMagnetPoles = 15,
|
||||
#ifdef FEATURE_SERIAL
|
||||
.swapFrontBack = false
|
||||
#endif
|
||||
};
|
||||
|
||||
constexpr Settings::ControllerHardware mosfetsOffControllerHardware {
|
||||
@ -50,9 +48,7 @@ constexpr Settings::ControllerHardware mosfetsOffControllerHardware {
|
||||
|
||||
.wheelDiameter = 165,
|
||||
.numMagnetPoles = 15,
|
||||
#ifdef FEATURE_SERIAL
|
||||
.swapFrontBack = false
|
||||
#endif
|
||||
};
|
||||
|
||||
constexpr Settings::WifiSettings defaultWifiSettings {
|
||||
@ -79,9 +75,7 @@ constexpr Settings::ControllerHardware spinnerControllerHardware {
|
||||
|
||||
.wheelDiameter = 165,
|
||||
.numMagnetPoles = 15,
|
||||
#ifdef FEATURE_SERIAL
|
||||
.swapFrontBack = false
|
||||
#endif
|
||||
};
|
||||
|
||||
constexpr Settings::BoardcomputerHardware::TimersSettings defaultTimersSettings {
|
||||
|
@ -51,9 +51,7 @@ struct Settings
|
||||
|
||||
int16_t wheelDiameter; // in mm
|
||||
int16_t numMagnetPoles; // virtual RPM per one real RPM
|
||||
#ifdef FEATURE_SERIAL
|
||||
bool swapFrontBack;
|
||||
#endif
|
||||
} controllerHardware;
|
||||
|
||||
struct BoardcomputerHardware {
|
||||
@ -144,9 +142,7 @@ void Settings::executeForEverySetting(T &&callable)
|
||||
|
||||
callable("wheelDiameter", controllerHardware.wheelDiameter);
|
||||
callable("numMagnetPoles", controllerHardware.numMagnetPoles);
|
||||
#ifdef FEATURE_SERIAL
|
||||
callable("swapFrontBack", controllerHardware.swapFrontBack);
|
||||
#endif
|
||||
|
||||
callable("sampleCount", boardcomputerHardware.sampleCount);
|
||||
callable("gasMin", boardcomputerHardware.gasMin);
|
||||
|
@ -56,12 +56,12 @@ struct WheelDiameterInchAccessor : public virtual AccessorInterface<float>
|
||||
void setValue(float value) override { settings.controllerHardware.wheelDiameter = convertFromInch(value); saveSettings(); }
|
||||
};
|
||||
struct NumMagnetPolesAccessor : public RefAccessorSaveSettings<int16_t> { int16_t &getRef() const override { return settings.controllerHardware.numMagnetPoles; } };
|
||||
#ifdef FEATURE_SERIAL
|
||||
struct SwapFrontBackAccessor : public RefAccessorSaveSettings<bool> {
|
||||
bool &getRef() const override { return settings.controllerHardware.swapFrontBack; }
|
||||
#ifdef FEATURE_SERIAL
|
||||
void setValue(bool value) override { RefAccessorSaveSettings<bool>::setValue(value); updateSwapFrontBack(); };
|
||||
};
|
||||
#endif
|
||||
};
|
||||
|
||||
struct SampleCountAccessor : public RefAccessorSaveSettings<int16_t> { int16_t &getRef() const override { return settings.boardcomputerHardware.sampleCount; } };
|
||||
struct GasMinAccessor : public RefAccessorSaveSettings<int16_t> { int16_t &getRef() const override { return settings.boardcomputerHardware.gasMin; } };
|
||||
|
@ -1,13 +1,12 @@
|
||||
#pragma once
|
||||
|
||||
#include <type_traits>
|
||||
#include <optional>
|
||||
|
||||
#include <HardwareSerial.h>
|
||||
#include <nvs_flash.h>
|
||||
#include <nvs.h>
|
||||
|
||||
#include <optional>
|
||||
|
||||
#include "settings.h"
|
||||
#ifdef FEATURE_BLUETOOTH
|
||||
#include "bluetoothmode.h"
|
||||
|
23
src/settingsutils.h
Normal file
23
src/settingsutils.h
Normal file
@ -0,0 +1,23 @@
|
||||
#pragma once
|
||||
|
||||
// Arduino includes
|
||||
#include <HardwareSerial.h>
|
||||
|
||||
// local includes
|
||||
#include "globals.h"
|
||||
#include "presets.h"
|
||||
|
||||
namespace {
|
||||
void switchProfile(uint8_t index)
|
||||
{
|
||||
settings = presets::defaultSettings;
|
||||
|
||||
if (settingsPersister.openProfile(index))
|
||||
{
|
||||
if (!settingsPersister.load(settings))
|
||||
Serial.println("switchProfile() load failed");
|
||||
}
|
||||
else
|
||||
Serial.println("switchProfile() openProfile failed");
|
||||
}
|
||||
}
|
@ -18,8 +18,10 @@ ContainerType gas, brems, avgSpeed, avgSpeedKmh, sumCurrent, frontVoltage, backV
|
||||
|
||||
void pushStats()
|
||||
{
|
||||
statistics::gas.push_back(gas);
|
||||
statistics::brems.push_back(brems);
|
||||
if (gas)
|
||||
statistics::gas.push_back(*gas);
|
||||
if (brems)
|
||||
statistics::brems.push_back(*brems);
|
||||
statistics::avgSpeed.push_back(avgSpeed);
|
||||
statistics::avgSpeedKmh.push_back(avgSpeedKmh);
|
||||
statistics::sumCurrent.push_back(sumCurrent);
|
||||
|
53
src/utils.h
53
src/utils.h
@ -265,7 +265,7 @@ void sendCommands()
|
||||
}
|
||||
#endif
|
||||
#ifdef FEATURE_CAN
|
||||
sendCanCommands();
|
||||
can::sendCanCommands();
|
||||
#endif
|
||||
}
|
||||
|
||||
@ -321,20 +321,55 @@ void updateAccumulators()
|
||||
}
|
||||
|
||||
void readPotis()
|
||||
{
|
||||
const auto sampleMultipleTimes = [](int pin){
|
||||
{
|
||||
[[maybe_unused]]
|
||||
constexpr auto sampleMultipleTimes = [](int pin){
|
||||
analogRead(pin);
|
||||
double sum{};
|
||||
for (int i = 0; i < settings.boardcomputerHardware.sampleCount; i++)
|
||||
const auto sampleCount = settings.boardcomputerHardware.sampleCount;
|
||||
for (int i = 0; i < sampleCount; i++)
|
||||
sum += analogRead(pin);
|
||||
return sum/settings.boardcomputerHardware.sampleCount;
|
||||
return sum / sampleCount;
|
||||
};
|
||||
|
||||
raw_gas = sampleMultipleTimes(PINS_GAS);
|
||||
gas = scaleBetween<float>(raw_gas, settings.boardcomputerHardware.gasMin, settings.boardcomputerHardware.gasMax, 0., 1000.);
|
||||
raw_gas = std::nullopt;
|
||||
raw_brems = std::nullopt;
|
||||
|
||||
raw_brems = sampleMultipleTimes(PINS_BREMS);
|
||||
brems = scaleBetween<float>(raw_brems, settings.boardcomputerHardware.bremsMin, settings.boardcomputerHardware.bremsMax, 0., 1000.);
|
||||
#ifdef FEATURE_CAN
|
||||
const auto now = millis();
|
||||
|
||||
if (can::can_gas)
|
||||
{
|
||||
if (now - can::last_can_gas < 100)
|
||||
raw_gas = *can::can_gas;
|
||||
else
|
||||
can::can_gas = std::nullopt;
|
||||
}
|
||||
|
||||
if (can::can_brems)
|
||||
{
|
||||
if (now - can::last_can_brems < 100)
|
||||
raw_brems = *can::can_brems;
|
||||
else
|
||||
can::can_brems = std::nullopt;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef FEATURE_ADC_IN
|
||||
if (!raw_gas)
|
||||
raw_gas = sampleMultipleTimes(PINS_GAS);
|
||||
if (!raw_brems)
|
||||
raw_brems = sampleMultipleTimes(PINS_BREMS);
|
||||
#endif
|
||||
|
||||
if (raw_gas)
|
||||
gas = scaleBetween<float>(*raw_gas, settings.boardcomputerHardware.gasMin, settings.boardcomputerHardware.gasMax, 0., 1000.);
|
||||
else
|
||||
gas = std::nullopt;
|
||||
if (raw_brems)
|
||||
brems = scaleBetween<float>(*raw_brems, settings.boardcomputerHardware.bremsMin, settings.boardcomputerHardware.bremsMax, 0., 1000.);
|
||||
else
|
||||
brems = std::nullopt;
|
||||
|
||||
#ifdef FEATURE_GAMETRAK
|
||||
raw_gametrakX = sampleMultipleTimes(PINS_GAMETRAKX);
|
||||
|
Reference in New Issue
Block a user