Compare commits

...

2 Commits

Author SHA1 Message Date
b16d941e62 PWM works 2025-12-08 16:03:17 +01:00
46077bcf1c made PWM 16bit 2025-12-08 15:32:02 +01:00
8 changed files with 183 additions and 80 deletions

BIN
EE-Editor-Project.eeproj Normal file

Binary file not shown.

View File

@@ -1,12 +1,17 @@
#include "MotorController.h"
// PWM-Top für Timer1 (Fast PWM, ICR1)
static constexpr uint16_t PWM_TOP = 4095; // 12-bit Auflösung, ~488 Hz bei Prescaler 8
// Default-Konfiguration
const MotorConfig_t defaultConfig = {
.minPWM = 0,
.maxPWM = 255,
.maxPWM = PWM_TOP,
.inverted = true,
.responseSpeed = 50, // ca. 50% pro Sekunde
.lookupTable = {0, 10, 20, 30, 40, 50, 60, 70, 80, 100} // 0..100% Kennlinie
.responseSpeedAccel = 50, // ca. 50% pro Sekunde Beschleunigung
.responseSpeedDecel = 200, // schnelleres Abbremsen
// Stark progressiv: viel Feingefühl unten, steiler Verlauf oben
.lookupTable = {0, 2, 5, 10, 18, 30, 45, 65, 85, 100}
};
MotorController::MotorController(const MotorSignals_t &signals)
@@ -14,13 +19,6 @@ MotorController::MotorController(const MotorSignals_t &signals)
{
loadDefaults();
// Pin initialisieren, falls sinnvoll
if (signals_.pwmPin >= 0)
{
pinMode(signals_.pwmPin, OUTPUT);
analogWrite(signals_.pwmPin, 0);
}
smoothedPromille = 0;
lastUpdateTime = millis();
lastPWM = 0;
@@ -32,28 +30,26 @@ MotorController::MotorController(const MotorSignals_t &signals)
void MotorController::setSignals(const MotorSignals_t &signals)
{
signals_ = signals;
// Bei neuer Verdrahtung ggf. PinMode setzen
if (signals_.pwmPin >= 0)
{
pinMode(signals_.pwmPin, OUTPUT);
}
}
void MotorController::loadDefaults()
{
config = defaultConfig;
// responseSpeed absichern
if (config.responseSpeed <= 0)
{
config.responseSpeed = 50; // Fallback
}
if (config.minPWM > PWM_TOP)
config.minPWM = PWM_TOP;
if (config.maxPWM > PWM_TOP)
config.maxPWM = PWM_TOP;
// Response-Werte absichern
if (config.responseSpeedAccel <= 0)
config.responseSpeedAccel = 50;
if (config.responseSpeedDecel <= 0)
config.responseSpeedDecel = config.responseSpeedAccel;
// min/max sanity
if (config.maxPWM < config.minPWM)
{
uint8_t tmp = config.minPWM;
uint16_t tmp = config.minPWM;
config.minPWM = config.maxPWM;
config.maxPWM = tmp;
}
@@ -68,18 +64,22 @@ void MotorController::setConfig(const MotorConfig_t &newConfig)
{
config = newConfig;
if (config.minPWM > PWM_TOP)
config.minPWM = PWM_TOP;
if (config.maxPWM > PWM_TOP)
config.maxPWM = PWM_TOP;
// min/max sanity
if (config.maxPWM < config.minPWM)
{
uint8_t tmp = config.minPWM;
uint16_t tmp = config.minPWM;
config.minPWM = config.maxPWM;
config.maxPWM = tmp;
}
if (config.responseSpeed <= 0)
{
config.responseSpeed = 50;
}
if (config.responseSpeedAccel <= 0)
config.responseSpeedAccel = 50;
if (config.responseSpeedDecel <= 0)
config.responseSpeedDecel = config.responseSpeedAccel;
}
void MotorController::maintain()
@@ -106,8 +106,9 @@ void MotorController::maintain()
// 3) Lookup-Interpolation von Prozent -> LUT-Prozent
const int16_t n = MotorConfig_t::lookupTableSize;
float pos = (adjustedSpeed / 100.0f) * (n - 1); // 0..(n-1) als float
int16_t lowerIndex = (int16_t)pos;
// Fixed-Point Interpolation: posScaled = adjustedSpeed * (n-1) (0..900)
int32_t posScaled = (int32_t)adjustedSpeed * (n - 1);
int16_t lowerIndex = posScaled / 100;
if (lowerIndex < 0)
lowerIndex = 0;
if (lowerIndex > n - 1)
@@ -117,27 +118,39 @@ void MotorController::maintain()
if (upperIndex > n - 1)
upperIndex = n - 1;
float frac = pos - lowerIndex; // 0..1 zwischen den beiden LUT-Punkten
int16_t fracPercent = posScaled - lowerIndex * 100; // 0..99
int16_t lowerPercent = config.lookupTable[lowerIndex];
int16_t upperPercent = config.lookupTable[upperIndex];
float lutPercent = lowerPercent + frac * (upperPercent - lowerPercent);
// lutPercentScaled in Prozent*100 (0..10000)
int32_t lutPercentScaled = (int32_t)lowerPercent * 100 +
(int32_t)(upperPercent - lowerPercent) * fracPercent;
// LUT liefert 0..100% -> auf PWM-Bereich skalieren
int16_t pwmLogical = map((int16_t)lutPercent, 0, 100, config.minPWM, config.maxPWM);
pwmLogical = constrain(pwmLogical, config.minPWM, config.maxPWM);
uint32_t pwmLogical = 0;
if (adjustedSpeed > 0)
{
uint32_t span = (uint32_t)config.maxPWM - (uint32_t)config.minPWM;
pwmLogical = config.minPWM;
if (span > 0)
{
// lutPercentScaled / 100 -> Prozent; skaliert auf span
pwmLogical = config.minPWM + (uint32_t)((lutPercentScaled * span + 5000UL) / 10000UL);
}
if (pwmLogical > config.maxPWM)
pwmLogical = config.maxPWM;
}
lastPWM = (uint8_t)pwmLogical;
// 4) PWM ausgeben
setPWM(lastPWM);
uint16_t pwmOut = computePwm((uint16_t)pwmLogical);
lastPWM = pwmOut;
// 5) Ausgänge in Signals spiegeln
if (signals_.currentSpeedPercent)
*signals_.currentSpeedPercent = adjustedSpeed;
if (signals_.currentPWM)
*signals_.currentPWM = lastPWM;
*signals_.currentPWM = pwmOut;
// 6) Debug-Ausgabe
printStatus();
@@ -151,8 +164,6 @@ void MotorController::stopMotor()
lastTargetPercent = 0;
lastPWM = 0;
setPWM(0);
if (signals_.currentSpeedPercent)
*signals_.currentSpeedPercent = 0;
@@ -171,48 +182,54 @@ int16_t MotorController::applyDynamicResponse(int16_t targetPercent)
}
targetPercent = constrain(targetPercent, 0, 100);
int16_t targetPromille = targetPercent * 10;
int32_t targetPromille = (int32_t)targetPercent * 10;
int32_t delta = targetPromille - smoothedPromille;
// responseSpeed = Prozent pro Sekunde → Promille pro Sekunde
int16_t maxChangePerSec = config.responseSpeed * 10;
int32_t maxChangePerSec = (delta >= 0 ? config.responseSpeedAccel : config.responseSpeedDecel) * 10L;
// maximaler Delta in diesem Zeitintervall
int16_t maxDelta = (int16_t)((maxChangePerSec * (int32_t)elapsedTime) / 1000L);
// maximaler Delta in diesem Zeitintervall (mit Rundung)
int32_t maxDelta = (maxChangePerSec * (int32_t)elapsedTime + 999) / 1000L;
if (maxDelta < 1)
maxDelta = 1; // minimale Änderung erlauben
int16_t delta = targetPromille - smoothedPromille;
if (delta > maxDelta)
delta = maxDelta;
else if (delta < -maxDelta)
delta = -maxDelta;
smoothedPromille += delta;
smoothedPromille += (int16_t)delta;
lastUpdateTime = currentTime;
return (smoothedPromille + 5) / 10; // runden
}
void MotorController::setPWM(uint8_t pwmLogical)
uint16_t MotorController::computePwm(uint16_t pwmLogical)
{
if (signals_.pwmPin < 0)
return;
// bei nicht invertierter Logik darf 0 auch unter minPWM fallen
if (!config.inverted && pwmLogical == 0)
return 0;
uint8_t pwmOut = pwmLogical;
uint32_t base = pwmLogical;
if (base < config.minPWM)
base = config.minPWM;
if (base > config.maxPWM)
base = config.maxPWM;
uint32_t pwmOut = base;
if (config.inverted)
{
// Logischer Wert im Bereich [min,max] wird gespiegelt
int16_t span = (int16_t)config.maxPWM - (int16_t)config.minPWM;
int16_t offset = (int16_t)pwmLogical - (int16_t)config.minPWM;
int16_t invOffset = span - offset;
int16_t inv = (int16_t)config.minPWM + invOffset;
if (inv < 0)
inv = 0;
if (inv > 255)
inv = 255;
pwmOut = (uint8_t)inv;
uint32_t span = (uint32_t)config.maxPWM - (uint32_t)config.minPWM;
uint32_t offset = base - (uint32_t)config.minPWM;
uint32_t inv = (uint32_t)config.minPWM + (span - offset);
pwmOut = inv;
}
analogWrite(signals_.pwmPin, pwmOut);
if (pwmOut > PWM_TOP)
pwmOut = PWM_TOP;
return (uint16_t)pwmOut;
}
void MotorController::printStatus()
@@ -232,8 +249,18 @@ void MotorController::printStatus()
Serial.print(lastSpeedPercent);
Serial.print("% pwm=");
Serial.print(lastPWM);
Serial.print(" resp=");
Serial.print(config.responseSpeed);
Serial.print(" min=");
Serial.print(config.minPWM);
Serial.print(" max=");
Serial.print(config.maxPWM);
Serial.print(" span=");
Serial.print((uint32_t)config.maxPWM - (uint32_t)config.minPWM);
Serial.print(" top=");
Serial.print(PWM_TOP);
Serial.print(" respA=");
Serial.print(config.responseSpeedAccel);
Serial.print(" respD=");
Serial.print(config.responseSpeedDecel);
Serial.print(" inv=");
Serial.println(config.inverted ? "Y" : "N");
}

View File

@@ -5,26 +5,24 @@
typedef struct MotorConfig
{
uint8_t minPWM;
uint8_t maxPWM;
uint16_t minPWM;
uint16_t maxPWM;
bool inverted;
int16_t responseSpeed; // Prozent pro Sekunde
int16_t responseSpeedAccel; // Prozent pro Sekunde beim Beschleunigen
int16_t responseSpeedDecel; // Prozent pro Sekunde beim Abbremsen
static const int16_t lookupTableSize = 10;
uint8_t lookupTable[lookupTableSize];
}MotorConfig_t;
} MotorConfig_t;
typedef struct MotorSignals
{
// Pin (by value)
int16_t pwmPin; // PWM-Ausgangspin, <0 = deaktiviert
// Eingänge
int16_t *targetSpeedPercent; // Sollwert 0..100%
bool *enabled; // optionaler Enable (true = aktiv)
// Ausgänge
int16_t *currentSpeedPercent; // Istwert 0..100%
uint8_t *currentPWM; // tatsächlicher PWM-Wert (logisch)
uint16_t *currentPWM; // tatsächlicher PWM-Wert (logisch 16-bit)
// Debug
bool *debugFlag; // globales Debug-Flag
@@ -54,13 +52,13 @@ private:
// interner Dynamik-State
int16_t smoothedPromille = 0; // 0..1000
uint32_t lastUpdateTime = 0;
uint8_t lastPWM = 0;
uint16_t lastPWM = 0;
uint32_t lastStatusPrint = 0;
int16_t lastTargetPercent = 0;
int16_t lastSpeedPercent = 0;
int16_t applyDynamicResponse(int16_t targetPercent);
void setPWM(uint8_t pwmLogical);
uint16_t computePwm(uint16_t pwmLogical);
void printStatus();
};

View File

@@ -7,7 +7,8 @@ static const PedalConfig_t defaultConfig = {
.minRaw = 230, // grob gedrückt
.maxRaw = 420, // grob nicht gedrückt
.calibrated = false,
.filterStrength = 3 // schnellerer Filter
.filterStrength = 3, // schnellerer Filter
.deadbandPercent = 5 // 0..5% unten ausblenden
};
// Tuning-Konstanten für die Auto-Cal
@@ -118,6 +119,22 @@ int16_t PedalController::mapRawToPercent(int16_t raw)
if (scaled > 100)
scaled = 100;
// einstellbares Totband am unteren Ende, optional auf restliche Spanne strecken
uint8_t db = config.deadbandPercent;
if (db > 80)
db = 80; // großzügige Obergrenze, um Division zu vermeiden
if (db > 0)
{
if (scaled <= db)
{
return 0;
}
// Restbereich auf 0..100 strecken, damit nicht oben "kürzt"
scaled = (scaled - db) * 100L / (100 - db);
if (scaled > 100)
scaled = 100;
}
return (int16_t)scaled;
}
@@ -481,6 +498,10 @@ void PedalController::setConfig(const PedalConfig_t &newConfig)
{
config.filterStrength = DEFAULT_FS;
}
if (config.deadbandPercent > 80)
{
config.deadbandPercent = 80;
}
if (config.maxRaw < config.minRaw)
{
@@ -500,6 +521,10 @@ void PedalController::loadDefaults()
{
config.filterStrength = DEFAULT_FS;
}
if (config.deadbandPercent > 80)
{
config.deadbandPercent = 80;
}
calState = IDLE;
calStep = 0;

View File

@@ -18,7 +18,8 @@ typedef struct PedalConfig
int16_t maxRaw;
bool calibrated;
uint8_t filterStrength;
}PedalConfig_t;
uint8_t deadbandPercent; // Totband unten in %, 0..80
} PedalConfig_t;
typedef struct PedalSignals
{

View File

@@ -1,5 +1,6 @@
#include <Arduino.h>
#include <EEPROM.h>
#include <avr/wdt.h>
#include "SerialController.h"
SerialController::SerialController(const SerialSignals_t &signals)
@@ -141,6 +142,14 @@ void SerialController::handleCommand(char *line)
return;
}
// Reset per Watchdog
if (strcmp(cmd, "RESET") == 0)
{
Serial.println(F("Resetting via watchdog..."));
triggerReset();
return;
}
// Debug toggle:
if (strcmp(cmd, "DEBUG") == 0)
{
@@ -302,11 +311,26 @@ void SerialController::cmdEepromRead(uint16_t addr)
Serial.println(printBuffer_);
}
void SerialController::triggerReset()
{
#if defined(__AVR__)
Serial.flush();
wdt_enable(WDTO_15MS); // shortest timeout to force reset quickly
while (true)
{
// wait for watchdog to fire
}
#else
Serial.println(F("Reset not supported on this platform."));
#endif
}
void SerialController::printHelp()
{
Serial.println(F("=== Serial Control Help ==="));
Serial.println(F("Basic commands (send + Enter):"));
Serial.println(F(" HELP - Show this help"));
Serial.println(F(" RESET - Restart controller via watchdog"));
Serial.println(F(" DEBUG - Toggle debug output"));
Serial.println(F(" CAL - Request auto-calibration"));
Serial.println(F(" SAVE - Request save settings to EEPROM"));

View File

@@ -42,6 +42,7 @@ private:
void handleCommand(char *line);
void cmdEepromWrite(uint16_t addr, uint8_t value);
void cmdEepromRead(uint16_t addr);
void triggerReset();
};
#endif

View File

@@ -20,7 +20,7 @@ const int16_t hallSensorPin = 3; // Hall sensor input
const int16_t encoderPinA = 4; // Encoder pin A
const int16_t encoderPinB = 5; // Encoder pin B
const int16_t encoderButtonPin = 2; // Encoder button
const int16_t motorPwmPin = 13; // Motor PWM pin
const int16_t motorPwmPin = 9; // Motor PWM pin
const int16_t pedalPinAnalog = A0; // Pedal analog Input pin
const int16_t pedalPinDigital = -1; // Pedal digital Input pin
@@ -30,7 +30,7 @@ bool debug = false;
// Globale Signale für Motor
int16_t gTargetSpeedPercent = 0; // Sollwert 0..100%
int16_t gCurrentSpeedPercent = 0; // Istwert 0..100%
uint8_t gCurrentPwm = 0; // aktueller PWM-Wert (logisch)
uint16_t gCurrentPwm = 0; // aktueller PWM-Wert (logisch, 16-bit)
bool gMotorEnabled = true;
// Globale Signale für Pedal
@@ -46,7 +46,6 @@ bool gSerialControl = false;
// Signals-Instanzen
MotorSignals_t motorSignals{
.pwmPin = motorPwmPin,
.targetSpeedPercent = &gTargetSpeedPercent,
.enabled = &gMotorEnabled,
.currentSpeedPercent = &gCurrentSpeedPercent,
@@ -115,6 +114,11 @@ void setup()
saveSettings(settings);
Serial.println(F("EEPROM Checksum mismatch, applied defaults"));
}
else
{
motor.setConfig(settings.motorConfig);
pedal.setConfig(settings.pedalConfig);
}
#ifdef DISPLAY_ENABLE
if (!display.begin(SSD1306_SWITCHCAPVCC, 0x3C))
@@ -200,6 +204,11 @@ void loop()
pedal.maintain();
// Motor nachführen
motor.maintain();
// PWM auf Timer1 ausgeben (OC1A / D9), MotorController liefert bereits invertiert/geklemmt
uint16_t pwmOut = gCurrentPwm;
if (pwmOut > 0x0FFF)
pwmOut = 0x0FFF;
OCR1A = pwmOut;
#ifdef DISPLAY_ENABLE
updateDisplay();
@@ -264,6 +273,24 @@ void updateDisplay()
void configurePWMFrequency()
{
// Configure Timer1 for higher PWM frequency (~4 kHz)
TCCR1B = (1 << CS11); // Set prescaler to 8
}
// Timer1 Fast PWM on OC1A (Pin D9)
// Mode 14: Fast PWM, TOP = ICR1
pinMode(motorPwmPin, OUTPUT);
TCCR1A = 0;
TCCR1B = 0;
// Non-inverting output on OC1A
TCCR1A |= (1 << COM1A1);
// Fast PWM, mode 14 (WGM13:0 = 1110)
TCCR1A |= (1 << WGM11);
TCCR1B |= (1 << WGM12) | (1 << WGM13);
// 12-bit Auflösung, niedrigere PWM-Frequenz (~488 Hz bei Prescaler 8)
ICR1 = 0x0FFF;
OCR1A = 0;
// Prescaler 8
TCCR1B |= (1 << CS11);
}