forked from esauvisky/OvenPIDController
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
Showing
1 changed file
with
112 additions
and
51 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,13 +1,15 @@ | ||
// Controlador PID para o forninho | ||
// Autor: Emiliano Sauvisky <[email protected]> | ||
// Controlador PID para o forninho/cultura bactéria | ||
// Autor: Emiliano Sauvisky <[email protected]> | ||
// Fork Alexandre <[email protected]> | ||
|
||
// TODO: Adicionar controles para mudar setPoint em tempo real | ||
// TODO: Testar ativar P_ON_M quando o gap entre input e setPoint for pequeno | ||
|
||
/************************** | ||
Bibliotecas | ||
**************************/ | ||
#include <max6675.h> | ||
//#include <max6675.h> | ||
#include <OneWire.h> | ||
#include <LiquidCrystal.h> | ||
#include <Wire.h> | ||
#include <PID_v1.h> | ||
|
@@ -16,11 +18,16 @@ | |
Definição de constantes | ||
**************************/ | ||
// Pinos do Módulo MAX6675 | ||
#define THERMO_GND 6 | ||
#define THERMO_VCC 5 | ||
#define THERMO_DO 4 | ||
#define THERMO_CS 3 | ||
#define THERMO_CLK 2 | ||
//#define THERMO_GND 6 | ||
//#define THERMO_VCC 5 | ||
//#define THERMO_DO 4 | ||
//#define THERMO_CS 3 | ||
//#define THERMO_CLK 2 | ||
|
||
|
||
// Pinos do Sensor DS18B20 | ||
OneWire ds(2); // on pin 2 (a 4.7K resistor is necessary) | ||
|
||
|
||
// Pinos do LCD | ||
#define LCD_RS 8 | ||
|
@@ -33,13 +40,18 @@ | |
// Símbolo ºC bonitinho para o LCD | ||
uint8_t degree[8] = {140, 146, 146, 140, 128, 128, 128, 128}; | ||
|
||
// Definições Sensor de temperatura DS18B20 | ||
byte i, present = 0,type_s, data[12], addr[8], addr2[8]; | ||
float celsius, fahrenheit; | ||
|
||
// Definições PID | ||
double temperature, setPoint, output; | ||
double temperature=10, setPoint=32, output; | ||
unsigned long lastTempUpdate, windowStartTime; | ||
#define WINDOW_SIZE 5000 | ||
#define MINIMUM_RELAY_TIME 500 | ||
#define RELAY_PIN A0 | ||
#define TEMP_READ_DELAY 250 | ||
#define ERRO_PIN A1 | ||
#define TEMP_READ_DELAY 1000 | ||
#define KP 45 | ||
#define KI 0.05 | ||
#define KD 20 | ||
|
@@ -48,7 +60,7 @@ unsigned long lastTempUpdate, windowStartTime; | |
Inicialização de Objetos | ||
***************************/ | ||
// Cria o objeto do MAX6675 | ||
MAX6675 thermocouple(THERMO_CLK, THERMO_CS, THERMO_DO); | ||
//MAX6675 thermocouple(THERMO_CLK, THERMO_CS, THERMO_DO); | ||
|
||
// Cria o objeto do LCD | ||
LiquidCrystal lcd(LCD_RS, LCD_EN, LCD_D4, LCD_D5, LCD_D6, LCD_D7); | ||
|
@@ -62,46 +74,91 @@ PID myPID(&temperature, &output, &setPoint, KP, KI, KD, DIRECT); | |
Atualiza a temperatura no menor tempo possível de acordo com o IC | ||
Retorna true se a temperatura foi atualizada | ||
Retorna false se ainda não passou o tempo para realizar nova leitura */ | ||
bool updateTemperature() { | ||
if ((millis() - lastTempUpdate) > TEMP_READ_DELAY) { | ||
temperature = thermocouple.readCelsius(); | ||
lastTempUpdate = millis(); | ||
return true; | ||
} | ||
return false; | ||
} | ||
void updateTemperature() { | ||
if ((millis() - lastTempUpdate) > TEMP_READ_DELAY) { | ||
|
||
ds.reset(); | ||
ds.select(addr); | ||
ds.write(0xBE); // Read Scratchpad | ||
for ( i = 0; i < 9; i++) { // we need 9 bytes | ||
data[i] = ds.read(); | ||
} | ||
|
||
ds.reset(); | ||
ds.select(addr); | ||
ds.write(0x44, 1); // start conversion, with parasite power on at the end | ||
lastTempUpdate = millis(); | ||
// Convert the data to actual temperature | ||
// because the result is a 16 bit signed integer, it should | ||
// be stored to an "int16_t" type, which is always 16 bits | ||
// even when compiled on a 32 bit processor. | ||
int16_t raw = (data[1] << 8) | data[0]; | ||
if (type_s) { | ||
raw = raw << 3; // 9 bit resolution default | ||
if (data[7] == 0x10) { | ||
// "count remain" gives full 12 bit resolution | ||
raw = (raw & 0xFFF0) + 12 - data[6]; | ||
} | ||
} else { | ||
byte cfg = (data[4] & 0x60); | ||
// at lower res, the low bits are undefined, so let's zero them | ||
if (cfg == 0x00) raw = raw & ~7; // 9 bit resolution, 93.75 ms | ||
else if (cfg == 0x20) raw = raw & ~3; // 10 bit res, 187.5 ms | ||
else if (cfg == 0x40) raw = raw & ~1; // 11 bit res, 375 ms | ||
//// default is 12 bit resolution, 750 ms conversion time | ||
} | ||
celsius = (float)raw / 16.0; | ||
temperature = celsius; | ||
} | ||
} | ||
|
||
/*************************** | ||
Pre-Configurações | ||
***************************/ | ||
void setup() { | ||
Serial.begin(9600); | ||
|
||
// Define a temperatura desejada | ||
setPoint = 32; | ||
|
||
// Define o pino do relay como um output | ||
pinMode(RELAY_PIN, OUTPUT); | ||
|
||
pinMode(ERRO_PIN, OUTPUT); | ||
|
||
// Aguarda a inicialização do DS18B20 | ||
while ( !ds.search(addr)) { | ||
ds.reset_search(); | ||
delay(250); | ||
} | ||
ds.reset(); // rest 1-Wire | ||
ds.select(addr); // select DS18B20 | ||
ds.write(0x4E); // write on scratchPad | ||
ds.write(0x00); // User byte 0 - Unused | ||
ds.write(0x00); // User byte 1 - Unused | ||
ds.write(0x7F); // set up en 9 bits 0x0F para 12 colocar (0x7F) | ||
ds.reset(); // reset 1-Wire | ||
//ds.reset(); | ||
ds.select(addr); | ||
ds.write(0x44, 1); // start conversion, with parasite power on at the end | ||
lastTempUpdate = millis(); | ||
|
||
// Inicia o módulo do LCD (2 linhas, 16 colunas por linha) | ||
lcd.begin(16, 2); | ||
|
||
// Cria o símbolo de graus ao LCD | ||
lcd.createChar(0, degree); | ||
lcd.clear(); | ||
|
||
// Seta o output do myPID entre 0 e WINDOW_SIZE. | ||
myPID.SetOutputLimits(0, WINDOW_SIZE); | ||
|
||
// Seta o sampling time para 125ms | ||
myPID.SetSampleTime(125); | ||
|
||
// Inicializa o PID | ||
myPID.SetMode(AUTOMATIC); | ||
|
||
/*************************** | ||
Pre-Configurações | ||
***************************/ | ||
void setup() { | ||
//Serial.begin(9600); | ||
|
||
// Define a temperatura desejada | ||
setPoint = 100; | ||
|
||
// Define o pino do relay como um output | ||
pinMode(RELAY_PIN, OUTPUT); | ||
|
||
// Ativa os pinos GND e VCC para o módulo MAX6675 | ||
pinMode(THERMO_VCC, OUTPUT); digitalWrite(THERMO_VCC, HIGH); | ||
pinMode(THERMO_GND, OUTPUT); digitalWrite(THERMO_GND, LOW); | ||
|
||
// Inicia o módulo do LCD (2 linhas, 16 colunas por linha) | ||
lcd.begin(16, 2); | ||
// Cria o símbolo de graus ao LCD | ||
lcd.createChar(0, degree); | ||
lcd.clear(); | ||
|
||
// Seta o output do myPID entre 0 e WINDOW_SIZE. | ||
myPID.SetOutputLimits(0, WINDOW_SIZE); | ||
// Seta o sampling time para 125ms | ||
myPID.SetSampleTime(125); | ||
// Inicializa o PID | ||
myPID.SetMode(AUTOMATIC); | ||
|
||
// Aguarda a inicialização do MAX6675 | ||
while (!updateTemperature) {}; | ||
} | ||
|
||
|
||
|
@@ -119,12 +176,16 @@ void loop() { | |
|
||
// Atualiza a temperatura | ||
updateTemperature(); | ||
|
||
|
||
|
||
|
||
// Roda o cálculo do PID | ||
myPID.Compute(); | ||
|
||
// Imprime a primeira linha do LCD (a temperatura atual) | ||
lcd.setCursor(0, 0); | ||
lcd.print("CurTemp:"); lcd.print(temperature); | ||
lcd.print("Temp:"); lcd.print(temperature); | ||
lcd.setCursor(14, 0); | ||
lcd.write((byte)0); lcd.print("C"); | ||
|
||
|