FRDM-K64F Code Share
/
PIDHeater
Extruder/Heated bed PID control for the FRDM-K64F
Revision 2:6e731a17523c, committed 2016-02-07
- Comitter:
- unix_guru
- Date:
- Sun Feb 07 19:08:57 2016 +0000
- Parent:
- 1:b852d582ad0e
- Commit message:
- FRDM-K64F - First version of PID heater control demo to manage temperature on a 3d printer extruder.
Changed in this revision
diff -r b852d582ad0e -r 6e731a17523c PID.lib --- a/PID.lib Wed Jan 27 21:32:34 2016 +0000 +++ b/PID.lib Sun Feb 07 19:08:57 2016 +0000 @@ -1,1 +1,1 @@ -https://developer.mbed.org/teams/FRDM-K64F-Code-Share/code/PID/#55bf0f813bb4 +https://developer.mbed.org/teams/FRDM-K64F-Code-Share/code/PID/#316f974b7f98
diff -r b852d582ad0e -r 6e731a17523c PIDHeater.cpp --- a/PIDHeater.cpp Wed Jan 27 21:32:34 2016 +0000 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,75 +0,0 @@ -#include "PIDHeater.h" - -PID controller(DEFAULT_Kp , DEFAULT_Ki , DEFAULT_Kd , 0.1); // Initialize PID controller -- Kc, Ti, Td, interval - - -PIDHeater::PIDHeater(PinName sensorPin, PinName pwmoutPin): thermistor(sensorPin), driver(pwmoutPin) { - - heaterOn = false; - controller.setInputLimits(0, 250); // MIN/MAX Temperature values - controller.setOutputLimits(0.0, 1.0); // Pwm output from 0.0 to 1.0 -// controller.setMode(AUTO); - controller.setSetPoint(22); // Set initial Temperature to 22 degrees celcius - } - -void PIDHeater::configureRange(float minTemperature, float maxTemperature) { - if (minTemperature < maxTemperature) { - minTemp = minTemperature; - maxTemp = maxTemperature; - controller.setInputLimits(minTemperature, maxTemperature); // MIN/MAX Temperature values - } -} - -float PIDHeater::getTemperature() { -#define THERMISTORNOMINAL 100000 // 100k -// temp. for nominal resistance (almost always 25 C) -#define TEMPERATURENOMINAL 25 -// The beta coefficient of the thermistor (usually 3000-4000) -#define BCOEFFICIENT 3950 -// the value of the 'other' resistor -#define SERIESRESISTOR 4700 - -// This is the workhorse routine that calculates the temperature -// using the Steinhart-Hart equation for thermistors -// https://en.wikipedia.org/wiki/Steinhart%E2%80%93Hart_equation - - float temperature, resistance; - float steinhart; - int a; - - a = thermistor.read_u16(); // Read 16bit Analog value -// pc.printf("Raw Analog Value for Thermistor = %d\r\n",a); - - /* Calculate the resistance of the thermistor from analog votage read. */ - resistance = (float) SERIESRESISTOR / ((65536.0 / a) - 1); -// pc.printf("Resistance for Thermistor = %f\r\n",resistance); - - steinhart = resistance / THERMISTORNOMINAL; // (R/Ro) - steinhart = log(steinhart); // ln(R/Ro) - steinhart /= BCOEFFICIENT; // 1/B * ln(R/Ro) - steinhart += 1.0 / (TEMPERATURENOMINAL + 273.15); // + (1/To) - steinhart = 1.0 / steinhart; // Invert - temperature = steinhart - 273.15; // convert to C - - return temperature; - -} - -bool PIDHeater::isHeaterOn() { - return heaterOn; -} - -void PIDHeater::run() { - getTemperature(); - driver = controller.compute(); -} - - -void PIDHeater::setTemperature(float temp) { - if (temp >= minTemp && temp <= maxTemp) { - desiredTemp = temp; - controller.setSetPoint(desiredTemp); // Set desired temperature in celcius - } -} - - \ No newline at end of file
diff -r b852d582ad0e -r 6e731a17523c PIDHeater.h --- a/PIDHeater.h Wed Jan 27 21:32:34 2016 +0000 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,43 +0,0 @@ -#ifndef PID_HEATER_H -#define PID_HEATER_H - -#include "mbed.h" - -#include "PID.h" -// These values were borrowed from Marlin Firmware defaults -#define DEFAULT_Kp 17.52 -#define DEFAULT_Ki 0.62 -#define DEFAULT_Kd 123.43 - - -/** A simple class for temperature control of a heater element using PID - * a heater driven via PWM digital output and one analog temperature sensor. - * - * Author(s): Michael Ball unix_guru@hotmail.com - * - */ -class PIDHeater{ - public: - /** Constructor receives pin names of the temperature sensor and - * the DigitalOut pin to which the heater driver is connected. */ - PIDHeater(PinName sensorPin, PinName digitalOutPin); - /** Set the temperature range of the sensor. */ - void configureRange(float minTemperature, float maxTemperature); - /** Read the current room temperature from the sensor. */ - float getTemperature(); - /** Test if the heater in turned ON. */ - bool isHeaterOn(); - /** Set the desired room temperature. */ - void setTemperature(float temp); - /** Attach run process to a timer */ - void run(); - - private: - AnalogIn thermistor; - DigitalOut driver; - Ticker ticker; - bool heaterOn; - float currentTemp, desiredTemp, minTemp, maxTemp, hysteresis, pwmValue; -}; - -#endif // HEATER_H \ No newline at end of file
diff -r b852d582ad0e -r 6e731a17523c main.cpp --- a/main.cpp Wed Jan 27 21:32:34 2016 +0000 +++ b/main.cpp Sun Feb 07 19:08:57 2016 +0000 @@ -1,39 +1,151 @@ /** A demo application to show how to mangage and control a heater element - * through a PID loop using a Thermistor input and PWM output. - * For more information on PID control + * through a PID loop using a Thermistor input and PWM output + * for the @NXP (@freescale) FRDM-K64F demo board. + * + * This particular example drives the heater element for a 3d Printer Extruder. + * + * For more information on PID control check out Brett Beauregard's Arduino PID library: + * + * https://github.com/br3ttb/Arduino-PID-Library + * + * The wikipedia article on PID controllers is a good place to start on + * understanding how they work: + * + * http://en.wikipedia.org/wiki/PID_controller + * + * The Thermistor value to Temerature routine uses the Steinhart-Hart equation. + This is a Thermistor to Temerature conversion demo + +Much thanks to @Adafruit for this tutorial: +https://learn.adafruit.com/thermistor/using-a-thermistor + +The 100K Thermistor is configured with a 4.7k series resistor +tied to vcc (3.3v) like this: + + +3.3v + | + \ + / 4.7k series resistor + \ + / + | + .-----------O To Anlog pin on FRDM board + | + \ + / + Thermistor 100k Nominal + \ + / + | + --- + GND * * Author(s): Michael Ball unix_guru@hotmail.com * */ #include "mbed.h" - -#include "PIDHeater.h" // PIDHeater simply takes two variables - // The Thermistor input and the Heater output. - // +#include "millis.h" +#include "PID.h" + +float getTemperature(); + Serial pc(USBTX, USBRX); -Ticker ticker; +Ticker PrintTicker; // Send process results to Console once per second +Ticker ticker; // Set up the millis() ticker. + +#define DEFAULT_Kp 1 +#define DEFAULT_Ki 0.002 +#define DEFAULT_Kd 20 -#define RATE 0.1 // Check temp every 100ms -PIDHeater extruder(A3, PTC3); // Thermistor on A3 heater on PTC3 +#define AUTOMATIC 1 +#define MANUAL 0 +#define DIRECT 0 +#define REVERSE 1 +#define thermistor A3 // FRDM-K64F Analog input pin A3 - Adjust to your particular board +#define driver PTC3 // FRDM-K64F PWM output pin PTC3 - Adjust to your particular board -void run_PID_loop() { // Periodically test temperature and set output - extruder.run(); +AnalogIn Thermistor(thermistor); // Read temperature value from thermistor on A3 +PwmOut Driver(driver); // PWM drive FET heater on PTC3 values are 0-1.0 + // For 0-100% + +float Input, Output, Setpoint; +PID controller(&Input, &Output, &Setpoint, DEFAULT_Kp , DEFAULT_Ki , DEFAULT_Kd , DIRECT); + +#define RATE 1.0 // Print rate Once per second + +void PrintValues() { // Routine to print out results to console + pc.printf("Input Output Setpoint Kp Ki Kd time\r\n"); + pc.printf("%f, %f, %f, %f, %f, %f, %d \r\n", + Input, Output, Setpoint, controller.GetKp() , controller.GetKi() , controller.GetKd() , millis() ); + } + int main(){ - extruder.configureRange(0,250); // Set MIN/MAX temperature in degrees Celcius. - extruder.setTemperature(25); // Set target temperature to 25 degrees Celcius. + startMillis(); // Initialize timer. + + pc.baud(115200); + pc.printf("\r\nThermistor PID Test - Build " __DATE__ " " __TIME__ "\r\n"); - ticker.attach(&run_PID_loop,RATE); // Start PID process running at 100ms rate. + PrintTicker.attach(&PrintValues,RATE); // Start PID process running at 100ms rate. + + Setpoint = 80; // Set target temperature in degrees Celcius. + controller.SetMode(AUTOMATIC); // Turn PID controller on. + while(1){ - pc.printf("Extruder Temperature is %f\r\n", extruder.getTemperature()); - - wait(1); + Input = getTemperature(); // Actual temperature in Degrees Celcius + + controller.Compute(); // Process PID loop. + + Driver = Output/1000; // Sent PWM value scaled 0 - 1.0 as mbed requires } -} \ No newline at end of file +} + + +// This is the workhorse routine that calculates the temperature +// using the Steinhart-Hart equation for thermistors +// https://en.wikipedia.org/wiki/Steinhart%E2%80%93Hart_equation + +float getTemperature() { +#define THERMISTORNOMINAL 100000 // 100k +// temp. for nominal resistance (almost always 25 C) +#define TEMPERATURENOMINAL 25 +// The beta coefficient of the thermistor (usually 3000-4000) +#define BCOEFFICIENT 3950 +// the value of the 'other' resistor +#define SERIESRESISTOR 4700 + +// This is the workhorse routine that calculates the temperature +// using the Steinhart-Hart equation for thermistors +// https://en.wikipedia.org/wiki/Steinhart%E2%80%93Hart_equation + + float temperature, resistance; + float steinhart; + int a; + + a = Thermistor.read_u16(); // Read 16bit Analog value +// pc.printf("Raw Analog Value for Thermistor = %d\r\n",a); + + /* Calculate the resistance of the thermistor from analog votage read. */ + resistance = (float) SERIESRESISTOR / ((65536.0 / a) - 1); +// pc.printf("Resistance for Thermistor = %f\r\n",resistance); + + steinhart = resistance / THERMISTORNOMINAL; // (R/Ro) + steinhart = log(steinhart); // ln(R/Ro) + steinhart /= BCOEFFICIENT; // 1/B * ln(R/Ro) + steinhart += 1.0 / (TEMPERATURENOMINAL + 273.15); // + (1/To) + steinhart = 1.0 / steinhart; // Invert + temperature = steinhart - 273.15; // convert to C + +// pc.printf("Extruder Temperature is %f\r\n", temperature); + + return temperature; + +} +
diff -r b852d582ad0e -r 6e731a17523c millis.lib --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/millis.lib Sun Feb 07 19:08:57 2016 +0000 @@ -0,0 +1,1 @@ +http://developer.mbed.org/teams/DFRobot/code/millis/#736e6cc31bcd