summaryrefslogtreecommitdiff
path: root/pcr-controller
diff options
context:
space:
mode:
authorBernhard Tittelbach <xro@realraum.at>2013-10-12 06:49:40 +0000
committerBernhard Tittelbach <xro@realraum.at>2013-10-12 06:49:40 +0000
commit2537498c60e85657987f3839f828cc80df30924e (patch)
tree2c821b16f3320ddc7ba8a23020dd6e0b59ad81e4 /pcr-controller
parentdoku (diff)
many more features for pcr controller
git-svn-id: https://svn.spreadspace.org/avr/trunk@243 aa12f405-d877-488e-9caf-2d797e2a1cc7
Diffstat (limited to 'pcr-controller')
-rw-r--r--pcr-controller/Makefile2
-rw-r--r--pcr-controller/cmd_queue.c113
-rw-r--r--pcr-controller/cmd_queue.h30
-rw-r--r--pcr-controller/pcr-controller.c157
-rw-r--r--pcr-controller/pid_control.c23
-rw-r--r--pcr-controller/pid_control.h15
-rw-r--r--pcr-controller/protocol_uc.txt13
-rw-r--r--pcr-controller/temp_curve.c116
-rw-r--r--pcr-controller/temp_curve.h35
9 files changed, 448 insertions, 56 deletions
diff --git a/pcr-controller/Makefile b/pcr-controller/Makefile
index 78400f6..1ed2909 100644
--- a/pcr-controller/Makefile
+++ b/pcr-controller/Makefile
@@ -22,7 +22,7 @@
NAME := pcr-controller
BOARD_TYPE := teensy2
-OBJ := $(NAME).o pwm.o pid_control.o
+OBJ := $(NAME).o pwm.o pid_control.o temp_curve.o cmd_queue.o
LIBS := util led lufa-descriptor-usbserial anyio onewire ds1820
EXTERNAL_LIBS := lufa
RESET_FUNC := ../tools/reset_lufa_cdc
diff --git a/pcr-controller/cmd_queue.c b/pcr-controller/cmd_queue.c
new file mode 100644
index 0000000..65cf001
--- /dev/null
+++ b/pcr-controller/cmd_queue.c
@@ -0,0 +1,113 @@
+/*
+ * r3PCR Teensy Controller Code
+ *
+ *
+ * Copyright (C) 2013 Bernhard Tittelbach <xro@realraum.at>
+ *
+ * This code is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * any later version.
+ *
+ * This code is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with spreadspace avr utils. If not, see <http://www.gnu.org/licenses/>.
+*/
+
+#include <stdlib.h>
+#include "cmd_queue.h"
+
+
+typedef struct {
+ uint8_t read_num_numbers;
+ void* function_ptr;
+} cmd_queue_item;
+
+#define CMQ_QUEUE_LENGTH 4
+cmd_queue_item cmd_queue_[CMQ_QUEUE_LENGTH];
+uint8_t cmd_queue_todo_pos_ = 0;
+uint8_t cmd_queue_next_here_ = 0;
+
+#define CMDQ_INPUT_LIST_LEN 2
+int16_t input_list_[CMDQ_INPUT_LIST_LEN];
+uint8_t num_args_read_ = 0;
+
+#define CMDQ_READBUFFER_LEN 20
+char cmdq_readbuffer_[CMDQ_READBUFFER_LEN];
+char *cmdq_readbuffer_pos_ = cmdq_readbuffer_;
+char *const cmdq_readbuffer_end_ = cmdq_readbuffer_ + (CMDQ_READBUFFER_LEN - 1);
+
+inline void cmdq_finishReadingArgument(void)
+{
+ *cmdq_readbuffer_pos_ = '\0';
+ cmdq_readbuffer_pos_ = cmdq_readbuffer_;
+ input_list_[num_args_read_++] = atoi(cmdq_readbuffer_);
+}
+
+//call regularily if in state CQ_READING
+uint8_t cmdq_addCharToArgumentBuffer(uint8_t c)
+{
+ if ( cmd_queue_todo_pos_ == cmd_queue_next_here_ )
+ return 1; //nothing to do with us
+ if (num_args_read_ >= CMDQ_INPUT_LIST_LEN)
+ return 1; //nothing to do with us
+ if (num_args_read_ >= cmd_queue_[cmd_queue_todo_pos_].read_num_numbers )
+ return 1; //nothing to do with us
+
+ //if input terminated by \n or \r then addArgument
+ if (c == '\n' || c == '\r')
+ {
+ cmdq_finishReadingArgument();
+ return 0;
+ } else { //continue reading
+ *cmdq_readbuffer_pos_ = (char) c;
+ cmdq_readbuffer_pos_++;
+ }
+ //if numlen of readbuffer reached, addArgument as well
+ if (cmdq_readbuffer_pos_ == cmdq_readbuffer_end_)
+ {
+ cmdq_finishReadingArgument();
+ return 0;
+ }
+ return 0;
+}
+
+void cmdq_queueCmdWithNumArgs(void* fptr, uint8_t num_args)
+{
+ if (num_args > CMDQ_INPUT_LIST_LEN)
+ return; //can't do that Would hang cmdq
+ cmd_queue_[cmd_queue_next_here_].read_num_numbers=num_args;
+ cmd_queue_[cmd_queue_next_here_].function_ptr=fptr;
+ cmd_queue_next_here_++;
+ cmd_queue_next_here_ %= CMQ_QUEUE_LENGTH;
+}
+
+void cmdq_doWork(void)
+{
+ if ( cmd_queue_todo_pos_ == cmd_queue_next_here_ )
+ return;
+
+ // is num_args_read_ now equal to num args we expect ?
+ if (num_args_read_ == cmd_queue_[cmd_queue_todo_pos_].read_num_numbers )
+ {
+ switch (num_args_read_)
+ {
+ case 0:
+ ((void(*)(void)) cmd_queue_[cmd_queue_todo_pos_].function_ptr)();
+ break;
+ case 1:
+ ((void(*)(int16_t)) cmd_queue_[cmd_queue_todo_pos_].function_ptr)(input_list_[0]);
+ break;
+ case 2:
+ ((void(*)(int16_t,int16_t)) cmd_queue_[cmd_queue_todo_pos_].function_ptr)(input_list_[0], input_list_[1]);
+ break;
+ }
+ num_args_read_ = 0;
+ cmd_queue_todo_pos_++;
+ cmd_queue_todo_pos_ %= CMQ_QUEUE_LENGTH;
+ }
+} \ No newline at end of file
diff --git a/pcr-controller/cmd_queue.h b/pcr-controller/cmd_queue.h
new file mode 100644
index 0000000..84b8a01
--- /dev/null
+++ b/pcr-controller/cmd_queue.h
@@ -0,0 +1,30 @@
+/*
+ * r3PCR Teensy Controller Code
+ *
+ *
+ * Copyright (C) 2013 Bernhard Tittelbach <xro@realraum.at>
+ *
+ * This code is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * any later version.
+ *
+ * This code is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with spreadspace avr utils. If not, see <http://www.gnu.org/licenses/>.
+*/
+
+#ifndef CMD_QUEUE_INCLUDE_H_
+#define CMD_QUEUE_INCLUDE_H_
+
+#include <avr/io.h>
+
+uint8_t cmdq_addCharToArgumentBuffer(uint8_t c);
+void cmdq_queueCmdWithNumArgs(void* fptr, uint8_t num_args);
+void cmdq_doWork(void);
+
+#endif \ No newline at end of file
diff --git a/pcr-controller/pcr-controller.c b/pcr-controller/pcr-controller.c
index 1aed20c..46d48ae 100644
--- a/pcr-controller/pcr-controller.c
+++ b/pcr-controller/pcr-controller.c
@@ -1,5 +1,5 @@
/*
- * OpenPCR Teensy Controller Code
+ * r3PCR Teensy Controller Code
*
*
* Copyright (C) 2013 Bernhard Tittelbach <xro@realraum.at>
@@ -27,7 +27,6 @@
#include <avr/interrupt.h>
#include <avr/power.h>
#include <stdio.h>
-#include <stdlib.h>
#include "util.h"
#include "led.h"
@@ -38,6 +37,8 @@
#include "pwm.h"
#include "pid_control.h"
+#include "temp_curve.h"
+#include "cmd_queue.h"
#define PIN_HIGH(PORT, PIN) PORT |= (1 << PIN)
#define PIN_LOW(PORT, PIN) PORT &= ~(1 << PIN)
@@ -61,6 +62,37 @@
uint8_t num_temp_sensors_ = 0;
int16_t raw_temp_ = 0;
uint8_t debug_ = 0;
+uint8_t monitor_temp_ = 0;
+// at f_system_clk = 10Hz, system_clk_ will not overrun for at least 13 years. PCR won't run that long
+uint32_t system_clk_ = 0;
+
+//with F_CPU = 16MHz and TIMER3 Prescaler set to /1024, TIMER3 increments with f = 16KHz. Thus if TIMER3 reaches 16, 1ms has passed.
+#define T3_MS *16
+//set TICK_TIME to 1/10 of a second
+#define TICK_TIME (100 T3_MS)
+
+ISR(TIMER3_COMPA_vect)
+{
+ //increment system_clk every TIME_TICK (aka 100ms)
+ system_clk_++;
+ //set up "clock" comparator for next tick
+ OCR3A = (OCR3A + TICK_TIME) & 0xFFFF;
+}
+
+void initSysClkTimer3(void)
+{
+ system_clk_ = 0;
+ // set counter to 0
+ TCNT3 = 0x0000;
+ // no outputs
+ TCCR3A = 0;
+ // Prescaler for Timer3: F_CPU / 1024 -> counts with f= 16KHz ms
+ TCCR3B = _BV(CS32) | _BV(CS30);
+ // set up "clock" comparator for first tick
+ OCR3A = TICK_TIME & 0xFFFF;
+ // enable interrupt
+ TIMSK3 = _BV(OCIE3A);
+}
void queryAndSaveTemperature(uint8_t bit_resolution)
{
@@ -114,28 +146,28 @@ void printTemperature(void)
}
}
-void readIntoBuffer(char *buffer, uint8_t buflen)
-{
- while (anyio_bytes_received() == 0);
- int ReceivedByte=0;
- do {
- ReceivedByte = fgetc(stdin);
- if (ReceivedByte != EOF)
- {
- *buffer = (char) ReceivedByte;
- buffer++;
- buflen --;
- }
- } while (ReceivedByte != '\n' && ReceivedByte != '\r' && buflen > 1);
- *buffer = 0;
-}
+//~ void readIntoBuffer(char *buffer, uint8_t buflen)
+//~ {
+ //~ while (anyio_bytes_received() == 0);
+ //~ int ReceivedByte=0;
+ //~ do {
+ //~ ReceivedByte = fgetc(stdin);
+ //~ if (ReceivedByte != EOF)
+ //~ {
+ //~ *buffer = (char) ReceivedByte;
+ //~ buffer++;
+ //~ buflen --;
+ //~ }
+ //~ } while (ReceivedByte != '\n' && ReceivedByte != '\r' && buflen > 1);
+ //~ *buffer = 0;
+//~ }
-int16_t readNumber(void)
-{
- char buffer[20];
- readIntoBuffer(buffer, 20);
- return atoi(buffer);
-}
+//~ int16_t readNumber(void)
+//~ {
+ //~ char buffer[20];
+ //~ readIntoBuffer(buffer, 20);
+ //~ return atoi(buffer);
+//~ }
void setPeltierCoolingDirectionPower(int16_t value)
{
@@ -143,7 +175,7 @@ void setPeltierCoolingDirectionPower(int16_t value)
value = 255;
if (value < -255)
value = -255;
-
+
if (value >= 0)
{
PIN_HIGH(PORTF, PELTIER_INA);
@@ -152,7 +184,7 @@ void setPeltierCoolingDirectionPower(int16_t value)
} else {
PIN_LOW(PORTF, PELTIER_INA);
PIN_HIGH(PORTB, PELTIER_INB);
- pwm_set((uint8_t) (-1 * value));
+ pwm_set((uint8_t) (-1 * value));
}
if (debug_)
printf("Peltier value: %d, INA: %d, INB: %d\r\n", value, (PORTF & _BV(PELTIER_INA)) > 0, (PORTB & _BV(PELTIER_INB)) > 0);
@@ -168,28 +200,38 @@ void handle_cmd(uint8_t cmd)
case 'R':
case 'r': reset2bootloader(); break;
case '?': debug_ = ~debug_; break;
+ case 'm': monitor_temp_ = ~monitor_temp_; break;
case '=': pid_setTargetValue(raw_temp_); break;
case '#': pid_setTargetValue(PID_DISABLED); break;
case 's': printTemperature(); return;
case 'L': led_toggle(); break;
+ case 'l': cmdq_queueCmdWithNumArgs(led_toggle, 0); break;
case 't':
printf("TargetTemp: ");
printRawTemp(pid_getTargetValue());
printf("\r\n");
return;
- case 'p':
+ case 'p':
case 'i':
case 'd':
pid_printVars();
return;
- case 'T': pid_setTargetValue(readNumber()); break;
- case 'P': pid_setP(readNumber()); break;
- case 'I': pid_setI(readNumber()); break;
- case 'D': pid_setD(readNumber()); break;
+ case 'T': cmdq_queueCmdWithNumArgs(pid_setTargetValue, 1); break;
+ case 'P': cmdq_queueCmdWithNumArgs(pid_setP, 1); break;
+ case 'I': cmdq_queueCmdWithNumArgs(pid_setI, 1); break;
+ case 'D': cmdq_queueCmdWithNumArgs(pid_setD, 1); break;
case 'A': PIN_HIGH(PORTB, PUMP_PIN); break;
- case 'a': PIN_LOW(PORTB, PUMP_PIN); break;
+ case 'a': PIN_LOW(PORTB, PUMP_PIN); break;
case 'B': PIN_HIGH(PORTD, TOPHEAT_PIN); break;
- case 'b': PIN_LOW(PORTD, TOPHEAT_PIN); break;
+ case 'b': PIN_LOW(PORTD, TOPHEAT_PIN); break;
+ case '-': //reset temp curve
+ tcurve_reset();
+ break;
+ case '+': //add temp curve entry
+ //~ tcurve_add(readNumber(), readNumber());
+ cmdq_queueCmdWithNumArgs(tcurve_add, 2);
+ break;
+ case 'Z': cmdq_queueCmdWithNumArgs(tcurve_setRepeats, 1); break;
default: printf("ERROR\r\n"); return;
}
printf("OK\r\n");
@@ -214,15 +256,19 @@ int main(void)
PINMODE_OUTPUT(DDRB, PELTIER_INB);
PINMODE_OUTPUT(DDRF, PELTIER_INA);
PINMODE_OUTPUT(DDRD, TOPHEAT_PIN);
-
+
pwm_init();
pwm_set(0);
-
+
pid_loadFromEEPROM();
num_temp_sensors_ = ds1820_discover();
-
- for(;;)
+
+ uint32_t last_time = 0;
+ uint32_t last_time2 = 0;
+ initSysClkTimer3(); //start system clock
+
+ for(;;)
{
int16_t BytesReceived = anyio_bytes_received();
while(BytesReceived > 0)
@@ -230,23 +276,44 @@ int main(void)
int ReceivedByte = fgetc(stdin);
if (ReceivedByte != EOF)
{
- handle_cmd(ReceivedByte);
+ // Ask cmdq_addCharToArgumentBuffer if it wants the current char, otherwise let handle_cmd() have it
+ if (cmdq_addCharToArgumentBuffer(ReceivedByte))
+ handle_cmd(ReceivedByte);
}
BytesReceived--;
}
-
- queryAndSaveTemperature(11);
-
- // PID control
- // FIXME: if we do USB Input / Output (input especially) we delay PID controll too mauch
- // that's bad, since the routing requires that it be called at exact intervalls
- // maybe we should use a interrupt routine
+ cmdq_doWork(); //may call queued functions
+
+ queryAndSaveTemperature(11); //at 11bit resolution, this takes at least 390ms
+
+ if (monitor_temp_)
+ printTemperature();
+
+ if (tcurve_isSet())
+ {
+ uint16_t time_elapsed = (uint16_t) (system_clk_ - last_time);
+ last_time = system_clk_;
+ //PID_DISABLED == TCURVE_ERROR so this works out fine and we disable heating and PID in this case
+ pid_setTargetValue(tcurve_getTempToSet(raw_temp_, time_elapsed));
+ if (debug_)
+ {
+ printf("time: %lu, elapsed: %u, target_temp: %d\r\n", system_clk_, time_elapsed, pid_getTargetValue());
+ }
+ }
+
+ // PID control
+ // make sure this is called at exact periodic intervals (i.e. make sure there are no large variable delays in for loop)
+ // e.g. enable periodic temp monitoring 'm' rather than querying temp at some intervall 's'
if (pid_isEnabled())
{
+ while (system_clk_ - last_time2 < 5 * TICK_TIME); //wait until at least 500ms have passed since last time. Should be enough time for everything else to finish. (after 13 years, code will hang here)
+ last_time2 = system_clk_;
setPeltierCoolingDirectionPower(pid_calc(raw_temp_));
}
-
+ else
+ setPeltierCoolingDirectionPower(0);
+
anyio_task();
}
}
diff --git a/pcr-controller/pid_control.c b/pcr-controller/pid_control.c
index 4ab3a99..18b2bc6 100644
--- a/pcr-controller/pid_control.c
+++ b/pcr-controller/pid_control.c
@@ -1,8 +1,21 @@
/*
- * OpenPCR Teensy Controller Code
+ * r3PCR Teensy Controller Code
*
*
* Copyright (C) 2013 Bernhard Tittelbach <xro@realraum.at>
+ *
+ * This code is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * any later version.
+ *
+ * This code is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with spreadspace avr utils. If not, see <http://www.gnu.org/licenses/>.
*/
#include "pid_control.h"
@@ -53,7 +66,7 @@ void pid_printVars(void)
void pid_setTargetValue(int16_t v)
{
- pid_target_value_ = v;
+ pid_target_value_ = v;
}
int16_t pid_getTargetValue(void)
@@ -75,13 +88,13 @@ int16_t pid_calc(int16_t current_value)
int32_t error = pid_target_value_ - current_value;
// derivative
// instead of derivative of error we take derivative on measurement
- // since dError/dt = - dInput/dt (note the - )
+ // since dError/dt = - dInput/dt (note the - )
int32_t d_measure = current_value - pid_last_input_;
pid_last_input_ = current_value;
// integral (bring pid_i_ into integral, so we get smooth transfer if pid_i_ suddenly changes)
pid_i_integralsum_ += pid_i_ * error;
-
+
// prevent integrator wind-up
if (pid_i_integralsum_ > pid_outlimit_max_)
pid_i_integralsum_ = pid_outlimit_max_;
@@ -92,7 +105,7 @@ int16_t pid_calc(int16_t current_value)
int32_t pid_output_preclamp = (
(error * pid_p_) + (pid_i_integralsum_) - (d_measure * pid_d_)
);
-
+
// limit output
if (pid_output_preclamp > pid_outlimit_max_)
return (int16_t) (pid_outlimit_max_ / PID_SCALE);
diff --git a/pcr-controller/pid_control.h b/pcr-controller/pid_control.h
index 4cff977..a3a4881 100644
--- a/pcr-controller/pid_control.h
+++ b/pcr-controller/pid_control.h
@@ -1,8 +1,21 @@
/*
- * OpenPCR Teensy Controller Code
+ * r3PCR Teensy Controller Code
*
*
* Copyright (C) 2013 Bernhard Tittelbach <xro@realraum.at>
+ *
+ * This code is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * any later version.
+ *
+ * This code is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with spreadspace avr utils. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef PID_CONTROLLER_INCLUDE_H_
diff --git a/pcr-controller/protocol_uc.txt b/pcr-controller/protocol_uc.txt
index c251da6..2ecfe0b 100644
--- a/pcr-controller/protocol_uc.txt
+++ b/pcr-controller/protocol_uc.txt
@@ -1,7 +1,7 @@
Command bytes:
-'s' Temperatursensor lesen -> string (float3.2) + \r\n
-'T' Temperatursoll setzen <- string (int(float(x)*16))
-'t' Temperatursoll lesen -> string (float3.2) + \r\n
+'s' Temperatursensor lesen -> parse_float(string("%3.2f")) + \r\n
+'T' Temperatursoll setzen <- string (int(float(temp)*16))
+'t' Temperatursoll lesen -> parse_float(string("%3.2f")) + \r\n
'P' P-Wert setzen <- string (uint16_t x * 1024)
'p' Alle PID Werte ausgeben -> string (uint16_t) + \r\n
'I' I-Wert setzen <- string (uint16_t x * 1024)
@@ -12,8 +12,13 @@ Command bytes:
'a' Pumpe off
'B' Deckelheizung on
'b' Deckelheizung off
-'L' LED (Debug) -> byte (0-255)
+'L' Toggle LED (Debug)
+'l' Toggle LED by using queuing system (Debug)
'R' Reset (Alle Register zurücksetzen und neu initialisieren)
+'-' Lösche gesetzte Temperaturkurve
+'+' Füge einen Punkt zur Temperaturkurve hinzu. erwartet Zieltemperatur und zeit (in10tel sekunden) für wie lange die temperatur gehalten werden soll bevor zur nächsten gesprungen wird. <- string(int(float(temp)*16)) \n <- string(int(seconds*10)) \n
+'Z' setzte Anzahl Zyklen in denen die Temperaturkurve wiederholt wird (0 == default == keine Wiederholung == 1 Zyklus, 1 == 1 Wiederholung == 2 Zyklen) <- string(int(repeats))
+'m' Schalte ständige Ausgabe der aktuellen Temperatur ein/aus
Nach jedem Setz-Command: Bestätigung mit "OK\r\n" (oder so)
'
diff --git a/pcr-controller/temp_curve.c b/pcr-controller/temp_curve.c
new file mode 100644
index 0000000..641f57c
--- /dev/null
+++ b/pcr-controller/temp_curve.c
@@ -0,0 +1,116 @@
+/*
+ * r3PCR Teensy Controller Code
+ *
+ *
+ * Copyright (C) 2013 Bernhard Tittelbach <xro@realraum.at>
+ *
+ * This code is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * any later version.
+ *
+ * This code is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with spreadspace avr utils. If not, see <http://www.gnu.org/licenses/>.
+*/
+
+#include "temp_curve.h"
+#include <stdlib.h>
+
+const int16_t temp_margin_ = 8; // 0.5 °C
+
+typedef struct tc_entry tc_entry;
+struct tc_entry {
+ int16_t target_temp;
+ uint16_t hold_for_timeticks;
+ tc_entry *next;
+};
+
+tc_entry *temp_curve_ = 0;
+tc_entry *temp_curve_end_ = 0;
+tc_entry *temp_curve_current_ = 0;
+
+uint16_t temp_stable_time_ = 0;
+
+uint8_t curve_num_repeats_ = 0;
+
+void tcurve_reset(void)
+{
+ tc_entry *curr = temp_curve_;
+ tc_entry *next = 0;
+ while (curr != 0) {
+ next = temp_curve_->next;
+ free(curr);
+ curr = next;
+ }
+ temp_curve_ = 0;
+ temp_curve_end_ = 0;
+ temp_curve_current_ = 0;
+ curve_num_repeats_ = 0;
+}
+
+uint8_t tcurve_hasFinished(void)
+{
+ return temp_curve_current_ == temp_curve_end_ && curve_num_repeats_ == 0;
+}
+
+uint8_t tcurve_isSet(void)
+{
+ return temp_curve_ != 0;
+}
+
+void tcurve_setRepeats(uint8_t r)
+{
+ curve_num_repeats_ = r;
+}
+
+void tcurve_add(int16_t temp, uint16_t hold_for_ticks)
+{
+ tc_entry *new_entry = malloc(sizeof(tc_entry));
+ new_entry->target_temp = temp;
+ new_entry->hold_for_timeticks = hold_for_ticks;
+ new_entry->next = 0;
+
+ if (temp_curve_end_ == 0)
+ {
+ temp_curve_end_ = new_entry;
+ temp_curve_ = new_entry;
+ temp_curve_current_ = new_entry;
+ } else {
+ temp_curve_end_->next = new_entry;
+ temp_curve_end_ = new_entry;
+ }
+}
+
+int16_t tcurve_getTempToSet(int16_t current_temp, uint16_t ticks_elapsed)
+{
+ if (temp_curve_current_ == 0)
+ return TCURVE_ERROR;
+
+ if (current_temp > temp_curve_current_->target_temp - temp_margin_ && current_temp < temp_curve_current_->target_temp + temp_margin_)
+ {
+ temp_stable_time_ += ticks_elapsed;
+ } // else: ignore the case of temp falling temporarily outside of temp_margin_
+
+ // if time has been stable for long enough, advance to next
+ // if there is no next, repeat curve until curve_num_repeats_ == 0
+ // once that happens, hold current temp forever
+ if (temp_stable_time_ >= temp_curve_current_->hold_for_timeticks)
+ {
+ if (temp_curve_current_->next != 0)
+ {
+ temp_curve_current_ = temp_curve_current_->next;
+ temp_stable_time_ = 0;
+ } else if (curve_num_repeats_)
+ {
+ //restart temp curve from the beginning
+ temp_curve_current_ = temp_curve_;
+ curve_num_repeats_--;
+ }
+ }
+ return temp_curve_current_->target_temp;
+} \ No newline at end of file
diff --git a/pcr-controller/temp_curve.h b/pcr-controller/temp_curve.h
new file mode 100644
index 0000000..39887cb
--- /dev/null
+++ b/pcr-controller/temp_curve.h
@@ -0,0 +1,35 @@
+/*
+ * rPCR Teensy Controller Code
+ *
+ *
+ * Copyright (C) 2013 Bernhard Tittelbach <xro@realraum.at>
+ *
+ * This code is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * any later version.
+ *
+ * This code is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with spreadspace avr utils. If not, see <http://www.gnu.org/licenses/>.
+*/
+
+#ifndef TEMP_CURVE_INCLUDE_H_
+#define TEMP_CURVE_INCLUDE_H_
+
+#define TCURVE_ERROR (1<<15)
+
+#include <avr/io.h>
+
+void tcurve_reset(void);
+void tcurve_setRepeats(uint8_t r);
+uint8_t tcurve_isSet(void);
+uint8_t tcurve_hasFinished(void);
+void tcurve_add(int16_t temp, uint16_t hold_for_s);
+int16_t tcurve_getTempToSet(int16_t current_temp, uint16_t time_elapsed);
+
+#endif \ No newline at end of file