Fixed the reflow.h file. It should have .cpp as well not just .h

This commit is contained in:
-help 2024-01-27 08:39:07 +02:00
parent 84c246d3d7
commit d79bf1025f
10 changed files with 456 additions and 88 deletions

54
src/PID/PidController.cpp Normal file
View File

@ -0,0 +1,54 @@
#include "PidController.h"
PidController::PidController(double *input, double *output, double *setpoint)
{
kp = 5;
kd = 10;
ki = 1;
controller.begin(input, output, setpoint, kp, ki, kd);
controller.reverse();
controller.setOutputLimits(25, 255);
controller.setSampleTime(20);
controller.setWindUpLimits(-100, 185);
controller.start();
}
double *PidController::compute()
{
controller.compute();
return controller.output;
}
void PidController::debug()
{
controller.debug(&Serial, " ", PRINT_INPUT | // Can include or comment out any of these terms to print
PRINT_OUTPUT | // in the Serial plotter
PRINT_SETPOINT | PRINT_BIAS | PRINT_P | PRINT_I | PRINT_D);
}
void PidController::debug2(const char* extraText)
{
controller.debug2(extraText,&Serial, " ", PRINT_INPUT | // Can include or comment out any of these terms to print
PRINT_OUTPUT | // in the Serial plotter
PRINT_SETPOINT | PRINT_BIAS | PRINT_P | PRINT_I | PRINT_D);
}
void PidController::stop()
{
controller.stop();
}

32
src/PID/PidController.h Normal file
View File

@ -0,0 +1,32 @@
#ifndef PIDCONTROLLER_H
#define PIDCONTROLLER_H
#include <Arduino.h>
#include <ArduPID.h>
class PidController
{
public:
PidController(double* input, double* output, double* setpoint);
void setSetpoint(double setpoint);
void setInput(double input);
double* compute();
void debug();
void debug2(const char* extraText);
void stop();
boolean started = false;
private:
ArduPID controller;
double kp;
double ki;
double kd;
double integral;
double previousError;
};
#endif // PIDCONTROLLER_H

View File

@ -1,11 +1,13 @@
#include "./oled.h"
#include <Arduino.h>
#include "../globals.h"
#include "oled.h"
#define SCREEN_WIDTH 128
#define SCREEN_HEIGHT 64
#define OLED_RESET -1 // Reset pin # (or -1 if sharing Arduino reset pin)
unsigned long lastProcessedReflowState = 0;
OledDisplay::OledDisplay()
{
@ -90,12 +92,28 @@ void OledDisplay::drawDebug()
display.setCursor(0, 0);
display.println("SysV: " + String(sysVoltage));
display.setCursor(0, 20);
display.println("In V: " + String(inputVoltage));
display.println("In V:" + String(inputVoltage));
display.setCursor(0, 40);
display.println("C°: " + String(thermistor1Temp));
display.display();
}
void OledDisplay::clearAll()
{
display.clearDisplay();
display.display();
}
void OledDisplay::warning(String message)
{
display.clearDisplay();
display.setCursor(0, 0);
display.setTextSize(2);
display.println("WARNING");
display.println(message);
display.display();
}
void OledDisplay::handleUserInputState()
{
Serial.println("USER_INPUT_STATE");

View File

@ -1,25 +1,31 @@
#ifndef __oled_h
#define __oled_h
#include <Adafruit_SSD1306.h>
#include "../reflow.h"
class OledDisplay {
public:
OledDisplay();
void setup();
void loop();
void teardown();
private:
Adafruit_SSD1306 display;
void drawDebug();
void handleUserInputState();
void handlePreheatState();
void handleSoakState();
void handleReflowState();
void handleCoolingState();
void handleFinishedState();
#include <Adafruit_SSD1306.h>
class OledDisplay
{
public:
OledDisplay();
void setup();
void loop();
void teardown();
void drawDebug();
void clearAll();
void warning(String message);
private:
Adafruit_SSD1306 display;
void handleUserInputState();
void handlePreheatState();
void handleSoakState();
void handleReflowState();
void handleCoolingState();
void handleFinishedState();
};
#endif

View File

@ -9,13 +9,18 @@
#include "leds/leds.h"
#include "reflow.h"
#include "displays/oled.h"
#include "globals.h"
#include "globals.h"
#include "PID/PidController.h"
#include "reflow.h"
WrappedState<ReflowProcessState> reflowProcessState = WrappedState<ReflowProcessState>(INITIALIZING);
// Define the analog ref used for the system voltage
AnalogRef analogRef(5.0);
OledDisplay oled = OledDisplay();
// Calibration data for 100K thermistor
TempCalibration calibration_100K_3950 = {25, 100000, 86, 10000, 170, 1000};
@ -28,6 +33,13 @@ TempCalibration calibration_100K_3950 = {25, 100000, 86, 10000, 170, 1000};
// Create an instance of the Adafruit ST7789 class using the custom SPI pins
Adafruit_ST7789 tft = Adafruit_ST7789(TFT_CS, TFT_DC, MOSI, SCK, TFT_RST);
#define MOSTFET_PIN 17
double currentTemp = 0;
double targetTemp = 60;
double pwmValue = 255;
PidController controller = PidController(&currentTemp, &pwmValue, &targetTemp);
// Initalize the 3950 100K thermistors with ACTUAL reference resistor measurnment(Measured between Left pin and GND when the board is powered off) using the default calibration data for 100K thermistor
Thermistor thermistor1(THERMISTOR1_PIN, 2500);
@ -41,18 +53,31 @@ Thermistor thermistor6(THERMISTOR6_PIN, 9000);
Buttons buttons = Buttons();
LEDS leds = LEDS();
// Declare the PID
ArduPID PID;
OledDisplay oled = OledDisplay();
ReflowProfile profile = ReflowProfile(new ReflowStep[5] {
ReflowStep(ReflowProcessState::PREHEAT, 2, 150),
ReflowStep(ReflowProcessState::SOAK, 3, 180),
ReflowStep(ReflowProcessState::REFLOW, 3, 220, EASE_IN_OUT),
ReflowStep(ReflowProcessState::COOL, 3, 100),
ReflowStep(ReflowProcessState::DONE, 0, 0)
}, "meow\0");
ReflowProfile profile = ReflowProfile(new ReflowStep[5]{
ReflowStep(ReflowProcessState::PREHEAT, 2, 100),
ReflowStep(ReflowProcessState::SOAK, 2, 140),
ReflowStep(ReflowProcessState::REFLOW, 2, 160, EASE_IN_OUT),
ReflowStep(ReflowProcessState::COOL, 2, 20),
ReflowStep(ReflowProcessState::DONE, 0, 0)},
"meow\0");
// Reflowprofile profile = Reflowprofile(new ReflowStep[5]{
// ReflowStep(ReflowProcessState::PREHEAT, 20, 50),
// ReflowStep(ReflowProcessState::SOAK, 35, 70),
// ReflowStep(ReflowProcessState::REFLOW, 20, 85),
// ReflowStep(ReflowProcessState::COOL, 20, 20),
// ReflowStep(ReflowProcessState::DONE, 0, 0)},
// "meow\0");
void setup()
{
pinMode(MOSTFET_PIN, OUTPUT);
analogWrite(MOSTFET_PIN, 255); // VERY IMPORTANT, DONT CHANGE!
Serial.begin(9600);
Serial.println("Starting OLED");
@ -61,10 +86,10 @@ void setup()
buttons.setup();
leds.setup();
oled.setup();
char name[20] = "meow\0";
// ReflowProfile profile = ReflowProfile::fromEEPROM(0);
// ReflowProfile profile = ReflowProfile(new ReflowStep[5] {
// ReflowStep(ReflowProcessState::PREHEAT, 30, 150),
// ReflowStep(ReflowProcessState::SOAK, 30, 180),
@ -75,7 +100,8 @@ void setup()
// profile.toEEPROM(0);
Serial.println(profile.name);
for (int i=0; i<5; i++) {
for (int i = 0; i < 5; i++)
{
Serial.print(profile.steps[i].duration);
Serial.print(" ");
Serial.println(profile.steps[i].targetTempAtEnd);
@ -90,31 +116,78 @@ void loop()
// Return the button that changed state
Pair<ButtonKind, StateChangeEvent<ButtonState>> *k = buttons.handleButtons();
if (k != NULL) {
if (k != NULL)
{
leds.handleButtonStateChange(*k);
if (ISBUTTONMIGRATEDTOSTATE(*k, ButtonKind::SELECT, ButtonState::PRESSED)) {
if (ISBUTTONMIGRATEDTOSTATE(*k, ButtonKind::SELECT, ButtonState::PRESSED))
{
reflowProcessState.set(ReflowProcessState::PREHEAT);
} else if (ISBUTTONMIGRATEDTOSTATE(*k, ButtonKind::BACK, ButtonState::PRESSED)) {
}
else if (ISBUTTONMIGRATEDTOSTATE(*k, ButtonKind::BACK, ButtonState::PRESSED))
{
reflowProcessState.set(ReflowProcessState::USER_INPUT);
} else if (ISBUTTONMIGRATEDTOSTATE(*k, ButtonKind::UP, ButtonState::PRESSED)) {
}
else if (ISBUTTONMIGRATEDTOSTATE(*k, ButtonKind::UP, ButtonState::PRESSED))
{
reflowProcessState.set(ReflowProcessState::COOL);
} else if (ISBUTTONMIGRATEDTOSTATE(*k, ButtonKind::DOWN, ButtonState::PRESSED)) {
}
else if (ISBUTTONMIGRATEDTOSTATE(*k, ButtonKind::DOWN, ButtonState::PRESSED))
{
reflowProcessState.set(ReflowProcessState::REFLOW);
}
}
ReflowStep step = profile.curReflowStep();
if (step.state != reflowProcessState.get()) {
if (step.state != reflowProcessState.get())
{
reflowProcessState.set(step.state);
}
oled.loop();
if (step.state == ReflowProcessState::DONE) {
profile.start();
return;
if (step.state == ReflowProcessState::DONE)
{
if (controller.started)
{
controller.stop();
}
Serial.println("DONE");
analogWrite(MOSTFET_PIN, 255);
}
Serial.print(String(STATE_STR(step.state)) + " " + String(step.duration) + " " + String(step.targetTempAtEnd) + " " + String(profile.getTargetTemp())+"\r");
}
else
{
// targetTemp = profile.getTargetTemp();
targetTemp = profile.getTargetTemp();
currentTemp = thermistor1.getTemperature();
controller.compute();
analogWrite(MOSTFET_PIN, pwmValue);
// controller.debug();
char myCharArray[50]; // Ensure this array is large enough to hold the string plus the null terminator
String(STATE_STR(step.state)).toCharArray(myCharArray, sizeof(myCharArray));
controller.debug2(myCharArray);
;
// Serial.print(String(STATE_STR(step.state)) + " " + String(step.duration) + " " + String(step.targetTempAtEnd) + " " + String(profile.timer.elapsed()) + " Step Time " + String(profile.getCurrentStepRelativeTime()) + " Target Temp:" + String(profile.targetTempReflow) + " % " + String(profile.percentage) + "\r");
};
// Serial.print("Targt temp: ");
// Serial.print(targetTemp);
oled.drawDebug();
// if (step.state == ReflowProcessState::DONE) {
// profile.start();
// return;
// }
// Serial.print(String(STATE_STR(step.state)) + " " + String(step.duration) + " " + String(step.targetTempAtEnd) + " " + " " + String(profile.timer.elapsed()) + "Step Time" + String(profile.getCurrentStepRelativeTime()) + " Current Temp:" + String(profile.getCurrentTemp()) +"\r");
// String(profile.getTargetTemp()) +
// Serial.print(String(STATE_STR(step.state)) + " " + String(step.duration) + " " + String(step.targetTempAtEnd) + " " + String(profile.getTargetTemp())+"\r");
}

View File

@ -3,8 +3,13 @@
#include "./common.h"
#include <EEPROM.h>
#include "StopWatch.h"
#include "thermistors/Thermistor.h"
#include "displays/oled.h"
extern Thermistor thermistor1;
// STATE MACHINE
enum ReflowProcessState
{
@ -18,13 +23,13 @@ enum ReflowProcessState
};
#define STATE_STR(state) (state == INITIALIZING ? "INITIALIZING" \
: state == USER_INPUT ? "USER_INPUT" \
: state == PREHEAT ? "PREHEAT" \
: state == SOAK ? "SOAK" \
: state == REFLOW ? "REFLOW" \
: state == COOL ? "COOL" \
: state == DONE ? "DONE" \
: "UNKNOWN")
: state == USER_INPUT ? "USER_INPUT" \
: state == PREHEAT ? "PREHEAT" \
: state == SOAK ? "SOAK" \
: state == REFLOW ? "REFLOW" \
: state == COOL ? "COOL" \
: state == DONE ? "DONE" \
: "UNKNOWN")
enum ReflowStepEaseFunction
{
@ -55,10 +60,14 @@ public:
{
case LINEAR:
return startTemp + (this->targetTempAtEnd - startTemp) * percentage;
case EASE_IN_OUT:
return startTemp + (this->targetTempAtEnd - startTemp) * -(cos(percentage * PI) - 1) / (double)2;
Serial.println(this->targetTempAtEnd);
case EASE_IN:
return startTemp + (this->targetTempAtEnd - startTemp) * (1 - cos(percentage * PI / (double)2));
case EASE_OUT:
return startTemp + (this->targetTempAtEnd - startTemp) * (sin(percentage * PI / (double)2));
}
@ -67,13 +76,31 @@ public:
#define PROFILE_SERIALIZED_SIZE 40
#define PROFILE_SERIALIZED_NAME_SIZE 20
class ReflowProfile
{
public:
uint8_t preheatEndTime;
uint8_t soakEndTime;
uint8_t reflowEndTime;
uint8_t coolEndTime;
int totalDuration;
float targetTempReflow;
float percentage;
ReflowProfile(ReflowStep steps[5], char name[20])
{
memcpy(this->steps, steps, 5 * sizeof(steps[0]));
memcpy(this->name, name, PROFILE_SERIALIZED_NAME_SIZE);
for (int i = 0; i < 5; i++)
{
this->steps[i] = steps[i];
}
for (int i = 0; i < 20; i++)
{
this->name[i] = name[i];
}
}
ReflowStep steps[5];
char name[20];
@ -81,54 +108,212 @@ public:
void start()
{
timer = StopWatch(StopWatch::Resolution::MILLIS);
timer = StopWatch(StopWatch::Resolution::SECONDS);
timer.start();
calculateEndTimes();
checkTotalTime();
}
/**
* Calculates the current reflow step based on the elapsed time
*/
ReflowStep curReflowStep() {
int8_t reflowStep = curReflowStepIndexAt(timer.elapsed());
if (reflowStep == -1) {
return steps[4]; // DONE
}
return steps[reflowStep];
// Make sure the total time does not exceed 254 seconds
//TODO: Fix overflow problem. Something is making the times and
void checkTotalTime(){
};
void calculateEndTimes()
{
preheatEndTime = steps[0].duration;
int soakEnd = steps[1].duration;
soakEndTime = preheatEndTime + soakEnd;
reflowEndTime = soakEndTime + steps[2].duration;
coolEndTime = reflowEndTime + steps[3].duration;
// reflowEndTime = soakEndTime + (steps[2].duration*1000);
// coolEndTime = reflowEndTime + (steps[3].duration*1000);
Serial.print("preheatEndTime: ");
Serial.println(preheatEndTime);
Serial.print("soakEndTime: ");
Serial.println(soakEndTime);
Serial.print("reflowEndTime: ");
Serial.println(reflowEndTime);
Serial.print("coolEndTime: ");
Serial.println(coolEndTime);
totalDuration = coolEndTime + steps[4].duration;
Serial.print("totalDuration: ");
Serial.println(totalDuration);
}
ReflowStep curReflowStep()
{
uint8_t elapsed = timer.elapsed();
int8_t curReflowStepIndexAt(uint32_t elapsed) {
for (int i = 0; i < 5; i++)
if (elapsed <= preheatEndTime)
{
if (elapsed < steps[i].duration * 1000)
{
return i;
}
else
{
elapsed -= steps[i].duration * 1000;
}
return steps[0];
}
else if (elapsed < soakEndTime)
{
return steps[1];
}
else if (elapsed < reflowEndTime)
{
return steps[2];
}
else if (elapsed < coolEndTime)
{
return steps[3];
}
else
{
return steps[4];
timer.stop();
timer.reset();
}
}
ReflowStep getPreviousSetep(ReflowStep step)
{
if (step.state == PREHEAT)
{
return steps[0];
}
else if (step.state == SOAK)
{
return steps[1];
}
else if (step.state == REFLOW)
{
return steps[2];
}
else if (step.state == COOL)
{
return steps[3];
}
else
{
return steps[4];
}
return -1; // we are done
}
float getTargetTemp()
{
uint32_t elapsedTime = timer.elapsed();
uint8_t startTemp = 20; // always assume 20 degrees at the start
int curStep = curReflowStepIndexAt(elapsedTime);
if (curStep == -1) {
ReflowStep curStep = curReflowStep();
ReflowStep prevStep = getPreviousSetep(curStep);
int currenStepIndex = getCurrentStepIndex(curStep);
int previousStepIndex = getCurrentStepIndex(prevStep);
float relativeTIme = calculateCurrentStepRelativeTime(curStep);
if (currenStepIndex == -1)
{
timer.reset();
timer.stop();
return startTemp; // We are done return 20 degrees
}
uint32_t relativeElapsedTime = elapsedTime;
for (int i=0; i<curStep; i++) {
relativeElapsedTime -= steps[i].duration * 1000;
for (int i = 0; i < currenStepIndex; i++)
{
relativeElapsedTime -= steps[i].duration;
startTemp = steps[i].targetTempAtEnd;
}
// Calculate percentage of current step
float percentage = (float)relativeElapsedTime / (float)(steps[curStep].duration * 1000);
return steps[curStep].calcTempAtPercentage(startTemp, percentage);
// float temp = curStep.calcTempAtPercentage(startTemp, percentage);
// Serial.print("relativeElapsedTime: ");
// Serial.println(relativeElapsedTime);
// Serial.print("relativeTIme: ");
// Serial.println(relativeTIme);
// Serial.print("startTemp: ");
// Serial.println(startTemp);
percentage = (float)relativeElapsedTime / (float)(steps[currenStepIndex].duration);
targetTempReflow = steps[currenStepIndex].calcTempAtPercentage(startTemp, percentage);
return targetTempReflow;
}
int getCurrentStepIndex()
{
uint8_t elapsed = timer.elapsed();
if (elapsed <= preheatEndTime)
{
return 0;
}
else if (elapsed < soakEndTime)
{
return 1;
}
else if (elapsed < reflowEndTime)
{
return 2;
}
else if (elapsed < coolEndTime)
{
return 3;
}
else
{
return 4;
}
}
int getCurrentStepIndex(ReflowStep step)
{
if (step.state == PREHEAT)
{
return 0;
}
else if (step.state == SOAK)
{
return 1;
}
else if (step.state == REFLOW)
{
return 2;
}
else if (step.state == COOL)
{
return 3;
}
else
{
return 4;
}
}
float getCurrentStepRelativeTime()
{
return calculateCurrentStepRelativeTime(curReflowStep());
};
float calculateCurrentStepRelativeTime(ReflowStep step)
{
uint8_t elapsed = timer.elapsed();
switch (step.state)
{
case PREHEAT:
return (float)elapsed;
case SOAK:
return (float)elapsed - preheatEndTime;
case REFLOW:
return (float)elapsed - soakEndTime;
case COOL:
return (float)elapsed - reflowEndTime;
case DONE:
return (float)elapsed - coolEndTime;
}
}
void toBuffer(uint8_t *b)
@ -161,7 +346,7 @@ public:
(ReflowProcessState)(i + PREHEAT),
b[PROFILE_SERIALIZED_NAME_SIZE + i * 3],
b[PROFILE_SERIALIZED_NAME_SIZE + 1 + i * 3],
(ReflowStepEaseFunction) b[PROFILE_SERIALIZED_NAME_SIZE + 2 + i * 3]);
(ReflowStepEaseFunction)b[PROFILE_SERIALIZED_NAME_SIZE + 2 + i * 3]);
}
return ReflowProfile(steps, name);
}

BIN
src/reflow.rar Normal file

Binary file not shown.

BIN
src/reflow2.rar Normal file

Binary file not shown.

View File

@ -26,11 +26,11 @@ Thermistor::~Thermistor()
{
}
int Thermistor::getTemperature()
float Thermistor::getTemperature()
{
// Get an average of 5 readings
int temp = 0;
float temp = 0;
uint8_t samples = 5;

View File

@ -49,7 +49,7 @@ public:
~Thermistor();
// Public Methods
int getTemperature();
float getTemperature();
float getResistance();
// Public Variables