summaryrefslogtreecommitdiff
path: root/pcr-controller
diff options
context:
space:
mode:
Diffstat (limited to 'pcr-controller')
-rw-r--r--pcr-controller/Makefile46
-rw-r--r--pcr-controller/cmd_queue.c131
-rw-r--r--pcr-controller/cmd_queue.h37
-rw-r--r--pcr-controller/pcr-controller.c385
-rw-r--r--pcr-controller/pid_control.c137
-rw-r--r--pcr-controller/pid_control.h39
-rw-r--r--pcr-controller/protocol_uc.txt117
-rw-r--r--pcr-controller/pwm.c87
-rw-r--r--pcr-controller/pwm.h11
-rw-r--r--pcr-controller/temp_curve.c177
-rw-r--r--pcr-controller/temp_curve.h40
11 files changed, 1207 insertions, 0 deletions
diff --git a/pcr-controller/Makefile b/pcr-controller/Makefile
new file mode 100644
index 0000000..399294e
--- /dev/null
+++ b/pcr-controller/Makefile
@@ -0,0 +1,46 @@
+##
+## spreadspace avr utils
+##
+##
+## Copyright (C) 2013-2014 Christian Pointner <equinox@spreadspace.org>
+##
+## This file is part of spreadspace avr utils.
+##
+## spreadspace avr utils 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.
+##
+## spreadspace avr utils 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/>.
+##
+
+NAME := pcr-controller
+BOARD_TYPE := teensy2
+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
+RESET_PARAM := 'R'
+
+LUFA_PATH := ../contrib/LUFA-120219
+LUFA_OPTS = -D USB_DEVICE_ONLY
+LUFA_OPTS += -D DEVICE_STATE_AS_GPIOR=0
+LUFA_OPTS += -D ORDERED_EP_CONFIG
+LUFA_OPTS += -D FIXED_CONTROL_ENDPOINT_SIZE=8
+LUFA_OPTS += -D FIXED_NUM_CONFIGURATIONS=1
+LUFA_OPTS += -D USE_FLASH_DESCRIPTORS
+LUFA_OPTS += -D USE_STATIC_OPTIONS="(USB_DEVICE_OPT_FULLSPEED | USB_OPT_REG_ENABLED | USB_OPT_AUTO_PLL)"
+LUFA_OPTS += -D INTERRUPT_CONTROL_ENDPOINT
+
+LUFA_OPTS += -D USB_MANUFACTURER="L\"xro\"" -D USB_MANUFACTURER_LEN=3
+LUFA_OPTS += -D USB_PRODUCT="L\"OLGA pcr-controller\"" -D USB_PRODUCT_LEN=19
+
+LUFA_COMPONENTS := USB USBCLASS SERIAL
+
+include ../include.mk
diff --git a/pcr-controller/cmd_queue.c b/pcr-controller/cmd_queue.c
new file mode 100644
index 0000000..b17235a
--- /dev/null
+++ b/pcr-controller/cmd_queue.c
@@ -0,0 +1,131 @@
+/*
+ * r3PCR Teensy Controller Code
+ *
+ *
+ * Copyright (C) 2013-2014 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 <stdio.h>
+#include "cmd_queue.h"
+
+//static assert:
+//~ static int SDFLKJ[sizeof(int) == sizeof(int16_t)] = { 0 };
+
+#define CMDQ_INPUT_LIST_LEN 2
+
+typedef struct {
+ uint8_t num_args;
+ uint8_t cmd;
+ void* function_ptr;
+ int16_t input_list[CMDQ_INPUT_LIST_LEN];
+ uint8_t num_args_read;
+} 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_fillargs_pos_ = 0;
+uint8_t cmd_queue_next_here_ = 0;
+
+
+
+#define CMDQ_READBUFFER_LEN 20
+char cmdq_readbuffer_[CMDQ_READBUFFER_LEN];
+uint8_t cmdq_readbuffer_pos_ = 0;
+
+inline void cmdq_finishReadingArgument(void)
+{
+ cmdq_readbuffer_[cmdq_readbuffer_pos_] = '\0';
+ cmdq_readbuffer_pos_ = 0;
+ cmd_queue_[cmd_queue_fillargs_pos_].input_list[cmd_queue_[cmd_queue_fillargs_pos_].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, since no cmd's queued
+ if (cmd_queue_[cmd_queue_fillargs_pos_].num_args_read >= CMDQ_INPUT_LIST_LEN)
+ return 1; //nothing to do with us
+ if (cmd_queue_[cmd_queue_fillargs_pos_].num_args_read >= cmd_queue_[cmd_queue_fillargs_pos_].num_args )
+ return 1; //nothing to do with us
+ //if input terminated by \n or \r then addArgument
+ if (c == '\n' || c == '\r' || c == ',' || c == 0x1B)
+ {
+ cmdq_finishReadingArgument();
+ return 0;
+ } else { //continue reading
+ cmdq_readbuffer_[cmdq_readbuffer_pos_++] = (char) c;
+ }
+ //if numlen +1 of readbuffer reached, addArgument as well (leave one char free to terminate with \0)
+ if (cmdq_readbuffer_pos_ +1 >= CMDQ_READBUFFER_LEN)
+ {
+ cmdq_finishReadingArgument();
+ }
+ return 0;
+}
+
+void cmdq_queueCmdWithNumArgs(void* fptr, uint8_t num_args, uint8_t cmd)
+{
+ if (num_args > CMDQ_INPUT_LIST_LEN)
+ {
+ printf("{\"cmd\":\"%c\",\"cmd_ok\":false,\"error\":\"max args == %d\"}\r\n", cmd, CMDQ_INPUT_LIST_LEN);
+ return; //to continue would hang cmdq, so we don't
+ }
+ if ((cmd_queue_next_here_ +1) % CMQ_QUEUE_LENGTH == cmd_queue_todo_pos_) //for this check REQUIRED: CMQ_QUEUE_LENGTH > 2
+ cmdq_doWork(); //no more space in queue -> execute now !
+ cmd_queue_[cmd_queue_next_here_].num_args = num_args;
+ cmd_queue_[cmd_queue_next_here_].cmd = cmd;
+ cmd_queue_[cmd_queue_next_here_].function_ptr = fptr;
+ cmd_queue_[cmd_queue_next_here_].num_args_read = 0;
+ cmd_queue_fillargs_pos_ = cmd_queue_next_here_;
+ cmd_queue_next_here_++;
+ cmd_queue_next_here_ %= CMQ_QUEUE_LENGTH;
+}
+
+void cmdq_doWork(void)
+{
+ while ( cmd_queue_todo_pos_ != cmd_queue_next_here_ )
+ {
+ // is num_args_read_ now equal to num args we expect ?
+ if (cmd_queue_[cmd_queue_todo_pos_].num_args_read != cmd_queue_[cmd_queue_todo_pos_].num_args )
+ break;
+ if (cmd_queue_[cmd_queue_todo_pos_].function_ptr == 0 )
+ break;
+
+ switch (cmd_queue_[cmd_queue_todo_pos_].num_args)
+ {
+ 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)(cmd_queue_[cmd_queue_todo_pos_].input_list[0]);
+ break;
+ case 2:
+ ((void(*)(int16_t,int16_t)) cmd_queue_[cmd_queue_todo_pos_].function_ptr)(cmd_queue_[cmd_queue_todo_pos_].input_list[0], cmd_queue_[cmd_queue_todo_pos_].input_list[1]);
+ break;
+ }
+ char cmd = cmd_queue_[cmd_queue_todo_pos_].cmd;
+ cmd_queue_[cmd_queue_todo_pos_].num_args_read = 0;
+ cmd_queue_[cmd_queue_todo_pos_].num_args = 0;
+ cmd_queue_[cmd_queue_todo_pos_].function_ptr = 0;
+ cmd_queue_[cmd_queue_todo_pos_].cmd = 0;
+ cmd_queue_todo_pos_++;
+ cmd_queue_todo_pos_ %= CMQ_QUEUE_LENGTH;
+ printf("{\"cmd\":\"%c\",\"cmd_ok\":true}\r\n",cmd);
+ }
+}
diff --git a/pcr-controller/cmd_queue.h b/pcr-controller/cmd_queue.h
new file mode 100644
index 0000000..9bd29db
--- /dev/null
+++ b/pcr-controller/cmd_queue.h
@@ -0,0 +1,37 @@
+/*
+ * r3PCR Teensy Controller Code
+ *
+ *
+ * Copyright (C) 2013-2014 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>
+
+/* The only actual reason for this queue is to enable non-blocking reads.
+* I.e. we want to avoid blocking the main loop while waiting on a user-input terminating '\n', '\r' or ',' .
+* As we could (and DO if the queue is full) execute a command right away once all arguments have been read,
+* the queue really does not need to be 4 long and the whole handling could me much much simpler.
+* I.e. only ever remember ONE command and execute it as soon as all args are present!
+*/
+
+uint8_t cmdq_addCharToArgumentBuffer(uint8_t c);
+void cmdq_queueCmdWithNumArgs(void* fptr, uint8_t num_args, uint8_t cmd);
+void cmdq_doWork(void);
+
+#endif
diff --git a/pcr-controller/pcr-controller.c b/pcr-controller/pcr-controller.c
new file mode 100644
index 0000000..d3b0ea6
--- /dev/null
+++ b/pcr-controller/pcr-controller.c
@@ -0,0 +1,385 @@
+/*
+ * r3PCR Teensy Controller Code
+ *
+ *
+ * Copyright (C) 2013-2014 Bernhard Tittelbach <xro@realraum.at>
+* uses avr-utils, anyio & co by Christian Pointner <equinox@spreadspace.org>
+ *
+ * This file is part of spreadspace avr utils.
+ *
+ * spreadspace avr utils 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.
+ *
+ * spreadspace avr utils 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 <avr/io.h>
+#include <avr/wdt.h>
+#include <avr/interrupt.h>
+#include <avr/power.h>
+#include <stdio.h>
+
+#include "util.h"
+#include "led.h"
+#include "anyio.h"
+
+#include "onewire.h"
+#include "ds1820.h"
+
+#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)
+#define PINMODE_OUTPUT PIN_HIGH //just use DDR instead of PORT
+#define PINMODE_INPUT PIN_LOW //just use DDR instead of PORT
+
+#define OP_SETBIT |=
+#define OP_CLEARBIT &= ~
+#define OP_CHECK &
+#define PIN_SW(PORTDDRREG, PIN, OP) PORTDDRREG OP (1 << PIN)
+
+#define HIGHv OP_SETBIT
+#define LOWv OP_CLEARBIT
+
+#define PELTIER_INA_PIN PINF7
+#define PELTIER_INA_PORT PORTF
+#define PELTIER_INA_DDR DDRF
+
+#define PELTIER_INB_PIN PINB6
+#define PELTIER_INB_PORT PORTB
+#define PELTIER_INB_DDR DDRB
+
+//OC1A
+#define PELETIER_PWM_EN_PIN PINB5
+#define PELETIER_PWM_EN_PORT PORTB
+#define PELETIER_PWM_EN_DDR DDRB
+
+//OC4D
+#define TOPHEAT_PIN PIND7
+#define TOPHEAT_PORT PORTD
+#define TOPHEAT_DDR DDRD
+
+#define PUMP_PIN PINC6
+#define PUMP_PORT PORTC
+#define PUMP_DDR DDRC
+
+#define ONEWIRE_PIN PINC7
+#define ONEWIRE_PINBASE PINC
+
+uint8_t num_temp_sensors_ = 0;
+int16_t raw_temp_ = 0;
+uint8_t temp_is_fresh_ = 0;
+uint8_t debug_ = 0;
+uint8_t monitor_temp_ = 0;
+uint8_t pump_autoon_ = 0;
+// at f_system_clk = 10Hz, system_clk_ will not overrun for at least 13 years. PCR won't run that long
+volatile 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 SYSCLKTICK_DURATION_IN_MS 100
+#define TICK_TIME (SYSCLKTICK_DURATION_IN_MS 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;
+ if (debug_)
+ led_toggle();
+}
+
+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)
+{
+ static uint32_t conversion_start_time = 0;
+ uint8_t sensor_index = 0;
+
+ if (num_temp_sensors_ == 0)
+ {
+ num_temp_sensors_ = ds1820_discover();
+ }
+
+ if (conversion_start_time == 0)
+ {
+ // -- trigger temperatur conversion in sensor
+ for (sensor_index=0; sensor_index < num_temp_sensors_; sensor_index++)
+ {
+ ds1820_set_resolution(sensor_index, bit_resolution);
+ ds1820_start_measuring(sensor_index);
+ }
+ conversion_start_time = system_clk_;
+ // -- end trigger
+ } else
+ if ( (system_clk_ - conversion_start_time)*SYSCLKTICK_DURATION_IN_MS > ds1820_get_conversion_time_ms(bit_resolution))
+ {
+ // -- receive temperatur after conversion time has passed
+ for (sensor_index=0; sensor_index < num_temp_sensors_; sensor_index++)
+ {
+ raw_temp_ = ds1820_read_temperature(sensor_index);
+ if (raw_temp_ != DS1820_ERROR)
+ {
+ temp_is_fresh_ = 1;
+ break; //we need only one successfully read value
+ }
+ }
+ conversion_start_time = 0;
+ // -- end receive
+ }
+}
+
+void printRawTemp(int16_t raw_temp)
+{
+ int16_t decimals = 100 * (raw_temp % 16) / 16;
+ if (decimals < 0)
+ decimals *= -1;
+ printf("%d.%02d", raw_temp / 16, decimals);
+}
+
+void printStatus(void)
+{
+ if (num_temp_sensors_ == 0)
+ {
+ printf("{\"cmd\":\"s\",\"cmd_ok\":false,\"error\": \"No DS1820 sensors on 1wire bus, thus no temperature\"}\r\n");
+ return;
+ }
+ if (raw_temp_ == DS1820_ERROR)
+ {
+ printf("{\"cmd\":\"s\",\"cmd_ok\":false,\"error\":\"talking to DS18b20, no valid temperature!\"}\r\n");
+ } else {
+ printf("{\"cmd\":\"s\",\"t\":%lu, \"currtemp\":", system_clk_);
+ printRawTemp(raw_temp_);
+ printf(", \"targettemp\":");
+ printRawTemp(pid_getTargetValue());
+ printf(", \"curve\":%s", (tcurve_isSet()?"true":"false"));
+ printf(", \"curve_t_elapsed\":%u", tcurve_getTimeElapsed());
+ printf(", \"cycles_left\":%u}\r\n", tcurve_getRepeatsLeft());
+ }
+}
+
+//~ 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);
+//~ }
+
+void setPeltierCoolingDirectionPower(int16_t value)
+{
+ if (value > 255)
+ value = 255;
+ if (value < -255)
+ value = -255;
+
+ if (value >= 0)
+ {
+ PIN_LOW(PELTIER_INA_PORT, PELTIER_INA_PIN);
+ PIN_HIGH(PELTIER_INB_PORT, PELTIER_INB_PIN);
+ pwm_b5_set((uint8_t) value);
+ } else {
+ PIN_HIGH(PELTIER_INA_PORT, PELTIER_INA_PIN);
+ PIN_LOW(PELTIER_INB_PORT, PELTIER_INB_PIN);
+ pwm_b5_set((uint8_t) (-1 * value));
+ }
+ if (debug_)
+ printf("Peltier value: %d, INA: %d, INB: %d, OCR1AH: %d, OCR1AL: %d\r\n", value, (PELTIER_INA_PORT & _BV(PELTIER_INA_PIN)) > 0, (PELTIER_INB_PORT & _BV(PELTIER_INB_PIN)) > 0, OCR1AH, OCR1AL);
+}
+
+void setTopHeaderValue(int16_t value)
+{
+ pwm_d7_set((uint8_t) (value & 0xFF));
+}
+
+void handle_cmd(uint8_t cmd)
+{
+ switch(cmd) {
+ case ' ':
+ case '\n':
+ case '\r':
+ return;
+ case 'R':
+ case 'r': reset2bootloader(); break;
+ case '?': debug_ = ~debug_; break;
+ case 'M': monitor_temp_ = 1; break;
+ case 'm': monitor_temp_ = 0; break;
+ case '=': pid_setTargetValue(raw_temp_); break;
+ case '#': pid_setTargetValue(PID_DISABLED); break;
+ case 't':
+ case 's': printStatus(); return;
+ case 'L': led_toggle(); break;
+ case 'l': cmdq_queueCmdWithNumArgs((void*) led_toggle, 0, cmd); return;
+ case 'p':
+ case 'i':
+ case 'd':
+ pid_printVars();
+ return;
+ case 'T': cmdq_queueCmdWithNumArgs((void*) pid_setTargetValue, 1, cmd); return;
+ case 'P': cmdq_queueCmdWithNumArgs((void*) pid_setP, 1, cmd); return;
+ case 'I': cmdq_queueCmdWithNumArgs((void*) pid_setI, 1, cmd); return;
+ case 'D': cmdq_queueCmdWithNumArgs((void*) pid_setD, 1, cmd); return;
+ case 'A':
+ PIN_HIGH(PUMP_PORT, PUMP_PIN);
+ pump_autoon_ = 0;
+ break;
+ case 'a':
+ PIN_LOW(PUMP_PORT, PUMP_PIN);
+ pump_autoon_ = 0;
+ break;
+ case 'B': cmdq_queueCmdWithNumArgs((void*) setTopHeaderValue, 1, cmd); return;
+ case 'b': setTopHeaderValue(0); break;
+ //~ case 'B': PIN_HIGH(TOPHEAT_PORT,TOPHEAT_PIN); break;
+ //~ case 'b': PIN_LOW(TOPHEAT_PORT,TOPHEAT_PIN); break;
+ case '@': pump_autoon_ = 1; break;
+ case '.': tcurve_printCurve(cmd); return;
+ case '-': //reset temp curve
+ tcurve_reset();
+ break;
+ case '+': //add temp curve entry
+ //~ tcurve_add(readNumber(), readNumber());
+ cmdq_queueCmdWithNumArgs((void*) tcurve_add, 2, cmd);
+ return;
+ case '>': cmdq_queueCmdWithNumArgs((void*) tcurve_setRepeatStartPosToLatestEntry, 0, cmd); return;
+ case '<': cmdq_queueCmdWithNumArgs((void*) tcurve_setRepeatEndPosToLatestEntry, 0, cmd); return;
+ case 'Z': cmdq_queueCmdWithNumArgs((void*) tcurve_setRepeats, 1, cmd); return;
+ default: printf("{\"cmd\":\"%c\",\"cmd_ok\":false,\"error\":\"unknown cmd\"}\r\n",cmd); return;
+ }
+ printf("{\"cmd\":\"%c\",\"cmd_ok\":true}\r\n",cmd);
+}
+
+int main(void)
+{
+ /* Disable watchdog if enabled by bootloader/fuses */
+ MCUSR &= ~(1 << WDRF);
+ wdt_disable();
+
+ cpu_init();
+ led_init();
+ anyio_init(115200, 0);
+ sei();
+
+ led_off();
+ owi_init(ONEWIRE_PIN, &ONEWIRE_PINBASE);
+ PINMODE_OUTPUT(PUMP_DDR, PUMP_PIN);
+ PIN_LOW(PUMP_PORT, PUMP_PIN);
+ PINMODE_OUTPUT(PELETIER_PWM_EN_DDR, PELETIER_PWM_EN_PIN);
+ PINMODE_OUTPUT(PELTIER_INB_DDR, PELTIER_INB_PIN);
+ PINMODE_OUTPUT(PELTIER_INA_DDR, PELTIER_INA_PIN);
+ PINMODE_OUTPUT(TOPHEAT_DDR, TOPHEAT_PIN);
+ PIN_LOW(TOPHEAT_PORT, TOPHEAT_PIN);
+
+ pwm_init();
+ pwm_b5_set(0);
+
+ pid_loadFromEEPROM();
+
+ num_temp_sensors_ = ds1820_discover();
+
+ uint32_t last_time = 0;
+ uint32_t last_time2 = 0;
+ initSysClkTimer3(); //start system clock
+
+ for(;;)
+ {
+ int16_t BytesReceived = anyio_bytes_received();
+ while(BytesReceived > 0)
+ {
+ int ReceivedByte = fgetc(stdin);
+ if (ReceivedByte != EOF)
+ {
+ // Ask cmdq_addCharToArgumentBuffer if it wants the current char, otherwise let handle_cmd() have it
+ if (cmdq_addCharToArgumentBuffer(ReceivedByte))
+ handle_cmd(ReceivedByte);
+ }
+ BytesReceived--;
+ }
+
+ cmdq_doWork(); //may call queued functions
+
+ queryAndSaveTemperature(11); //at 11bit resolution
+
+ if (temp_is_fresh_)
+ {
+ temp_is_fresh_ = 0; //once used, temp is used up ;->
+
+ if (monitor_temp_)
+ printStatus();
+
+ 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));
+ }
+
+ // 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())
+ {
+ if (pump_autoon_)
+ PIN_HIGH(PUMP_PORT, PUMP_PIN);
+ if (debug_)
+ printf("pid_calc..");
+ while (system_clk_ - last_time2 < 5); //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)
+ if (debug_)
+ printf(" clk: %lu, elaps: %lu\r\n",system_clk_ , system_clk_ - last_time2);
+ last_time2 = system_clk_;
+ temp_is_fresh_ = 0;
+ setPeltierCoolingDirectionPower(pid_calc(raw_temp_));
+ }
+ else
+ {
+ setPeltierCoolingDirectionPower(0);
+ if (pump_autoon_)
+ PIN_LOW(PUMP_PORT, PUMP_PIN);
+ }
+ }
+
+ anyio_task();
+ }
+}
diff --git a/pcr-controller/pid_control.c b/pcr-controller/pid_control.c
new file mode 100644
index 0000000..6ab275b
--- /dev/null
+++ b/pcr-controller/pid_control.c
@@ -0,0 +1,137 @@
+/*
+ * r3PCR Teensy Controller Code
+ *
+ *
+ * Copyright (C) 2013-2014 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"
+
+#include <avr/eeprom.h>
+
+EEMEM int32_t pid_p_eeprom_;
+EEMEM int32_t pid_i_eeprom_;
+EEMEM int32_t pid_d_eeprom_;
+EEMEM int32_t crc_eeprom_;
+
+#define PID_SCALE 1024L
+
+int32_t pid_outlimit_min_ = -255 * PID_SCALE;
+int32_t pid_outlimit_max_ = 255 * PID_SCALE;
+
+int32_t pid_p_ = 8192;
+int32_t pid_i_ = 512;
+int32_t pid_d_ = 24576;
+
+int32_t pid_i_integralsum_ = 0;
+int32_t pid_last_input_ = 0;
+
+int16_t pid_target_value_ = PID_DISABLED;
+
+void pid_setP(int16_t p)
+{
+ pid_p_ = (int32_t) p;
+ pid_saveToEEPROM();
+}
+
+void pid_setI(int16_t i)
+{
+ pid_i_ = (int32_t) i;
+ pid_saveToEEPROM();
+}
+
+void pid_setD(int16_t d)
+{
+ pid_d_ = (int32_t) d;
+ pid_saveToEEPROM();
+}
+
+void pid_printVars(void)
+{
+ printf("{\"PID_P\":%d, \"PID_I\":%d, \"PID_D\":%d, \"PID_SCALE\":%d}\r\n", (int16_t) (pid_p_), (int16_t) (pid_i_), (int16_t) (pid_d_), (int16_t) PID_SCALE);
+}
+
+void pid_setTargetValue(int16_t v)
+{
+ pid_target_value_ = v;
+}
+
+int16_t pid_getTargetValue(void)
+{
+ return pid_target_value_;
+}
+
+int pid_isEnabled(void)
+{
+ return pid_target_value_ != PID_DISABLED;
+}
+
+// PRE-CONDITION: call pid_calc at exactly regular intervals !!
+int16_t pid_calc(int16_t current_value)
+{
+ if (pid_target_value_ == PID_DISABLED)
+ return PID_DISABLED;
+
+ int32_t error = (int32_t) pid_target_value_ - (int32_t) current_value;
+ // derivative
+ // instead of derivative of error we take derivative on measurement
+ // since dError/dt = - dInput/dt (note the - )
+ int32_t d_measure = (int32_t) current_value - pid_last_input_;
+ pid_last_input_ = (int32_t) 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_;
+ else if (pid_i_integralsum_ < pid_outlimit_min_)
+ pid_i_integralsum_ = pid_outlimit_min_;
+
+ // combine factors (insofar as we did not already do it above)
+ 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);
+ else if (pid_output_preclamp < pid_outlimit_min_)
+ return (int16_t) (pid_outlimit_min_ / PID_SCALE);
+ else
+ return (int16_t) (pid_output_preclamp / PID_SCALE);
+}
+
+void pid_loadFromEEPROM(void)
+{
+ int32_t p = eeprom_read_dword((uint32_t *) &pid_p_eeprom_);
+ int32_t i = eeprom_read_dword((uint32_t *) &pid_i_eeprom_);
+ int32_t d = eeprom_read_dword((uint32_t *) &pid_d_eeprom_);
+ int32_t crc = eeprom_read_dword((uint32_t *) &crc_eeprom_);
+ if (crc == (p ^ i ^ d)) {
+ pid_p_ = p;
+ pid_i_ = i;
+ pid_d_ = d;
+ }
+}
+
+void pid_saveToEEPROM(void)
+{
+ eeprom_write_dword((uint32_t *) &pid_p_eeprom_, pid_p_);
+ eeprom_write_dword((uint32_t *) &pid_i_eeprom_, pid_i_);
+ eeprom_write_dword((uint32_t *) &pid_d_eeprom_, pid_d_);
+ eeprom_write_word((uint16_t *) &crc_eeprom_, pid_p_ ^ pid_i_ ^ pid_d_);
+}
diff --git a/pcr-controller/pid_control.h b/pcr-controller/pid_control.h
new file mode 100644
index 0000000..1d45925
--- /dev/null
+++ b/pcr-controller/pid_control.h
@@ -0,0 +1,39 @@
+/*
+ * r3PCR Teensy Controller Code
+ *
+ *
+ * Copyright (C) 2013-2014 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_
+#define PID_CONTROLLER_INCLUDE_H_
+
+#include <stdio.h>
+
+#define PID_DISABLED (1<<15)
+
+void pid_setP(int16_t p);
+void pid_setI(int16_t i);
+void pid_setD(int16_t d);
+void pid_printVars(void);
+void pid_setTargetValue(int16_t v);
+int pid_isEnabled(void);
+int16_t pid_getTargetValue(void);
+int16_t pid_calc(int16_t current_value);
+void pid_loadFromEEPROM(void);
+void pid_saveToEEPROM(void);
+
+#endif
diff --git a/pcr-controller/protocol_uc.txt b/pcr-controller/protocol_uc.txt
new file mode 100644
index 0000000..6326454
--- /dev/null
+++ b/pcr-controller/protocol_uc.txt
@@ -0,0 +1,117 @@
+==== Command bytes ====
+'s' Temperatursensor lesen -> parse_float(string("%3.2f")) + \r\n
+'t' Same as above
+'T' Set PID target temperature. <-TempValue
+ (Only works if no temperature curve is set.)
+'P' Set PID value P <-PIDValue
+'I' Set PID value I <-PIDValue
+'D' Set PID value D <-PIDValue
+'p' Print all PID values as JSON string
+'i' Same as above
+'d' Same as above
+'A' Switch on pump.
+'a' Switch pump off.
+'@' Switch pump on automatically if temp goes higher than 30°C or lower than 19°C
+'B' Set top heater PWM to value between 0 and 255 (in future pwm value may be fixed and 'B' may return to simple on switch) <-IntValue
+'b' Switch top heater off.
+'L' Toggle LED (Debug)
+'l' Toggle LED by using queuing system (Debug)
+'R' Reset microcontroller
+'r' Same as above
+'=' Set PID target temperature to current temperature.
+'-' Clear temperature curve.
+'.' Print out currently programmed temperature curve as JSON string.
+'+' Add a temperature curve point. <-TempValue <-Duration
+ Excpects 2 arguments: Targettemperature and duration for which that temperature is to be held after it has been reached.
+'>' Set the last added (with '+') temperature curve point to be the cycle start point.
+ E.g. if >0 curve repetitions are set (with 'Z') the repetitions will start here, instead of at the first added curve point.
+'<' Set the last added (with '+') temperature curve point to be the cycle end point.
+ E.g. this and any temperature points added after this marker will not be repeated, but programmed after the main loop
+'Z' Set number of cycle repetitions <-IntValue
+ E.g: 0 == default == no repetitions == 1 cycle
+ 1 == 1 repetitions == 2 cycles)
+ ....
+'M' Enable periodic status output as JSON string.
+'m' Disable periodic status output as JSON string.
+'?' Toggle Debug Output.
+'#' Disable PID (i.e. set PID target temperature to -2048.00)
+ (Only works if no temperature curve is set. If needed use '-' first.)
+
+
+==== Command arguments ====
+If arguments are required they are to be given as numeric string.
+
+Temperature is given in degrees celcsius multiplied by 16, thus allowing us to set decimal degrees by storing and transmitting integer values.
+Negative temperatures are prepended by '-'.
+E.g. a temperature of -20 °C would be input as -320.
+
+PID parpameters are multiplied by 1024 (or whatever PID_SCALE is set to).
+E.g. an I value of 0.5 would be input as 512.
+
+Duration or time values are input as 100ms (1/10th second) integer values.
+E.g. a duration of 2 seconds would be input as 20.
+
+If multiple arguments are required, they are to be separated by the comma character ','.
+
+<-IntValue ...means: string(uint16_t x)
+<-TempValue ...means: string(int16_t(float temp * 16))
+<-PIDValue ...means: string(uint16_t x * 1024)
+<-Duration ...means: string(uint16_t s * 10)
+
+
+==== Command responses ====
+are formated as JSON values.
+PID Values are output just like they are expected to be input.
+Temperatures are output as formated float values in °C, expect when printing the current temperature curve when temperatures are printed as internal integer values (see TempValue)
+
+A value of -2048.00 or -32768 generally means something is DISABLED or inapplicable in the current state.
+
+
+==== Example uc Answers ====
+Responses to "s":
+{"cmd":"s","t":503, "currtemp":20.34, "targettemp":-2048.00, "curve":false, "curve_t_elapsed":0, "cycles_left":0} //curve and pid disabled (pid disabel when targettemp == -2048.00
+{"cmd":"s","t":97000, "currtemp":40.34, "targettemp":70.00, "curve":true, "curve_t_elapsed":14, "cycles_left":11}
+{"cmd":"s","t":97200, "currtemp":69.72, "targettemp":70.00, "curve":true, "curve_t_elapsed":214, "cycles_left":11}
+{"cmd":"s","t":110123, "currtemp":30.14, "targettemp":30.00, "curve":true, "curve_t_elapsed":10, "cycles_left":9}
+{"cmd":"s","t":9999999, "currtemp":5.02, "targettemp":5.00, "curve":true, "curve_t_elapsed":65535, "cycles_left":0} //we know all is finished because targettemp is hold-temp
+
+Response to "."
+{"cmd":".","curve":[{"temp":1520,"duration":9000,"is_curr":1,"is_loop_start":0,"is_loop_end":0},{"temp":1040,"duration":10,"is_curr":0,"is_loop_start":1,"is_loop_end":0},{"temp":960,"duration":300,"is_curr":0,"is_loop_start":0,"is_loop_end":0},{"temp":1120,"duration":300,"is_curr":0,"is_loop_start":0,"is_loop_end":0},{"temp":1120,"duration":1000,"is_curr":0,"is_loop_start":0,"is_loop_end":1},0],"end_temp":80,"loop_repeats":30}
+
+Response to other commands:
+{"cmd":"s","cmd_ok":false,"error": "No DS1820 sensors on 1wire bus, thus no temperature"}
+{"cmd":"s","cmd_ok":false,"error":"talking to DS18b20, no valid temperature!"}
+{"cmd":"A","cmd_ok":true}
+{"cmd":"a","cmd_ok":true}
+{"cmd":"#","cmd_ok":true}
+
+
+==== Example Program ====
+s
+-
+=
+@
+b
++1536,300
+>
++448,300
++1152,300
+<
+Z30
++64,9999
+M
+
+The sequence of above commands
+- prints current temperature
+- deletes any currenlty set temperature curve
+- instructs the PID controller to hold the current temperature
+- set the pump to auto
+- switch off top heater
+- programms the following temperature curve: [ 96°C (30s) -> 28°C (30s) -> 72°C (30s) ]
+- sets the curve to repeat the items in >< brackets 30 times
+- programms final holding temperature of 4°C (note that duration of last entry does not really matter since it will always be held indefinately).
+- activates periodic status output.
+
+
+(c) Bernhard Tittelbach, 2013
+
diff --git a/pcr-controller/pwm.c b/pcr-controller/pwm.c
new file mode 100644
index 0000000..3ca5bbe
--- /dev/null
+++ b/pcr-controller/pwm.c
@@ -0,0 +1,87 @@
+
+#include "pwm.h"
+
+//OutputCompareRegister for Timer1 and pin OC1A/B5
+#define PWMB5_VAL OCR1AL
+//for FastPWM in Timer4 OCR4C is TOP for all OC4x pins, all other PWM Modes use OCR4A,OCR4B or OCR4D
+#define PWMD7_VAL OCR4D
+
+void pwm_init(void)
+{
+ //for OC1A on pin B5
+ DDRB |= (1<<PB5);
+ TCCR1A = 0;
+ TCNT1 = 0;
+ OCR1A = 0;
+ TCCR1A = (1<<WGM10); //Fast PWM, 8-bit
+ TCCR1B = (1<<WGM12); //Fast PWM, 8-bit
+ //TCCR1A |= (1<<COM1A1) // Clear OCnA/OCnB/OCnC on compare match when up-counting. Set OCnA/OCnB/OCnC on compare match when downcounting. (for FastPWM)
+
+ //for OC4D on pin D7
+ DDRD |= (1<<PD7);
+ TCCR4A = 0;
+ TCCR4B = 0;
+ TCCR4C = _BV(PWM4D); //Fast PWM: PWM4x == 0x1 && WGM41..40 ==0x00
+ TCCR4D = 0; //Fast PWM: PWM4x == 0x1 && WGM41..40 ==0x00
+ TCNT4 = 0;
+ OCR4C = 0xFF; //TOP value
+ OCR4D = 0;
+}
+
+inline void pwm_b5_on(void)
+{
+ TCCR1A |= (1<<COM1A1); // Clear OCnA/OCnB/OCnC on compare match when up-counting. Set OCnA/OCnB/OCnC on compare match when downcounting.
+ TCCR1B = (TCCR1B & 0xF8) | (1<<CS10); // enable timer clock, no prescaling
+}
+
+inline void pwm_d7_on(void)
+{
+ TCCR4B = (TCCR4B & 0xF0) | (1<<CS40); // enable timer clock, no prescaling
+ TCCR4C |= (1<<COM4D1); // Clear OC4D on compare match when up-counting. Set when when TCNT4 == 0x000 (for FastPWM)
+}
+
+inline void pwm_b5_off(void)
+{
+ TCCR1A &= ~((1<<COM1A1) | (1<<COM1A0)); //normal port operation
+ TCCR1B = (TCCR1B & 0xF8); //no clock source, timer stopped
+ TCNT1 = 0;
+ PORTB &= ~(1 << PB5); //set pin to LOW (otherwise it will remain in state since last pwm toggle)
+}
+
+inline void pwm_d7_off(void)
+{
+ TCCR4B = (TCCR4B & 0xF0); //no clock source, timer stopped
+ TCCR4C &= ~(_BV(COM4D1) | _BV(COM4D0)); //normal port operation
+ TCNT4 = 0;
+ PORTD &= ~(1 << PD7); //set pin to LOW (otherwise it will remain in state since last pwm toggle)
+}
+
+void pwm_b5_set(uint8_t val)
+{
+ if (val > 0)
+ pwm_b5_on();
+ else
+ pwm_b5_off();
+ PWMB5_VAL = val;
+}
+
+void pwm_d7_set(uint8_t val)
+{
+ if (val > 0)
+ pwm_d7_on();
+ else
+ pwm_d7_off();
+ PWMD7_VAL = val;
+}
+
+inline void pwm_b5_inc(void)
+{
+ if(PWMB5_VAL < 255)
+ PWMB5_VAL++;
+}
+
+inline void pwm_b5_dec(void)
+{
+ if(PWMB5_VAL > 0)
+ PWMB5_VAL--;
+}
diff --git a/pcr-controller/pwm.h b/pcr-controller/pwm.h
new file mode 100644
index 0000000..2459cd3
--- /dev/null
+++ b/pcr-controller/pwm.h
@@ -0,0 +1,11 @@
+#ifndef PWM_H_INCLUDED_
+#define PWM_H_INCLUDED_
+
+#include <avr/io.h>
+
+void pwm_init(void);
+void pwm_b5_set(uint8_t val);
+void pwm_d7_set(uint8_t val);
+
+
+#endif
diff --git a/pcr-controller/temp_curve.c b/pcr-controller/temp_curve.c
new file mode 100644
index 0000000..29db29e
--- /dev/null
+++ b/pcr-controller/temp_curve.c
@@ -0,0 +1,177 @@
+/*
+ * r3PCR Teensy Controller Code
+ *
+ *
+ * Copyright (C) 2013-2014 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>
+#include <stdio.h>
+
+extern uint8_t debug_;
+
+const int16_t temp_margin_ = 16; // 1 °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; //pointer to start of curve (so we can free it by going through the list)
+tc_entry *temp_curve_end_ = 0; //pointer to last added entry in curve (so we know can quickly append new entries)
+tc_entry *temp_curve_current_ = 0; //pointer to currently active entry (temp we currently hold)
+tc_entry *temp_curve_loop_first_ = 0; //pointer to start of loop (loop is a subset of curve list)
+tc_entry *temp_curve_loop_last_ = 0; //pointer to end of loop (loop is a subset of curve list)
+
+uint16_t temp_stable_time_ = 0;
+
+uint8_t temp_curve_original_num_repeats_ = 0;
+uint8_t curve_loop_num_repeats_ = 0; // number of times the loop still needs to be reapeated before finishing the rest of the curve
+
+void tcurve_reset(void)
+{
+ tc_entry *curr = temp_curve_;
+ tc_entry *next = 0;
+ while (curr != 0) {
+ next = curr->next;
+ if (debug_)
+ printf("tcreset: curr: 0x%x, next: 0x%x, end: 0x%x\r\n",(uint16_t)curr,(uint16_t)next,(uint16_t)temp_curve_end_);
+ free(curr);
+ if (curr == temp_curve_end_)
+ break; //just to be sure
+ curr = next;
+ }
+ temp_curve_ = 0;
+ temp_curve_end_ = 0;
+ temp_curve_current_ = 0;
+ temp_curve_original_num_repeats_ = 0;
+ curve_loop_num_repeats_ = 0;
+ temp_curve_loop_first_ = temp_curve_;
+ temp_curve_loop_last_ = 0;
+ if (debug_)
+ printf("tcreset: done\n\n");
+}
+
+uint16_t tcurve_getTimeElapsed(void)
+{
+ return temp_stable_time_;
+}
+
+uint8_t tcurve_getRepeatsLeft(void)
+{
+ return curve_loop_num_repeats_;
+}
+
+uint8_t tcurve_isSet(void)
+{
+ return temp_curve_ != 0;
+}
+
+void tcurve_setRepeats(uint8_t r)
+{
+ curve_loop_num_repeats_ = r;
+ temp_curve_original_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;
+ temp_curve_loop_first_ = new_entry;
+ } else {
+ temp_curve_end_->next = new_entry;
+ temp_curve_end_ = new_entry;
+ }
+}
+
+void tcurve_setRepeatStartPosToLatestEntry(void)
+{
+ //calling this again, overwrites last set loop start entry
+ temp_curve_loop_first_= temp_curve_end_;
+ //no loop_last_ before loop_first_
+ temp_curve_loop_last_ = 0;
+}
+
+void tcurve_setRepeatEndPosToLatestEntry(void)
+{
+ //calling this again, overwrites last set loop stop entry
+ temp_curve_loop_last_ = temp_curve_end_;
+}
+
+void tcurve_printCurve(uint8_t cmd)
+{
+ if (temp_curve_ == 0)
+ {
+ printf("{\"cmd\":\"%c\",\"cmd_ok\":false,\"error\":\"No curve set\"}\r\n",cmd);
+ return;
+ }
+ printf("{\"cmd\":\"%c\",\"curve\":[",cmd);
+ for (tc_entry *ce = temp_curve_; ; ce=ce->next)
+ {
+ printf("{\"temp\":%d,\"duration\":%u,\"is_curr\":%d,\"is_loop_start\":%d,\"is_loop_end\":%d},",
+ ce->target_temp,
+ ce->hold_for_timeticks,
+ ce == temp_curve_current_,
+ ce == temp_curve_loop_first_,
+ ce == temp_curve_loop_last_);
+
+ if (ce == temp_curve_end_)
+ break;
+ }
+ printf("0],\"loop_repeats\":%d}\r\n", temp_curve_original_num_repeats_);
+}
+
+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 temp has been stable for the set amount of timeticks in current curve element
+ if (temp_stable_time_ >= temp_curve_current_->hold_for_timeticks)
+ {
+ temp_stable_time_ = 0;
+
+ if (curve_loop_num_repeats_ && //if repetitions left
+ ( (temp_curve_loop_last_ != 0 && temp_curve_current_ == temp_curve_loop_last_) //and we have reached a set loop endpoint
+ || temp_curve_current_->next == 0 //or the end of the list
+ ))
+ { //go back to first point in loop
+ curve_loop_num_repeats_--;
+ temp_curve_current_ = temp_curve_loop_first_;
+ } else if (temp_curve_current_->next != 0) //else if elements left in curve list
+ { // go to next element
+ temp_curve_current_ = temp_curve_current_->next;
+ }
+ //else stay on temperature of last element forever (until reset is called or new elements are added)
+ }
+ return temp_curve_current_->target_temp;
+}
diff --git a/pcr-controller/temp_curve.h b/pcr-controller/temp_curve.h
new file mode 100644
index 0000000..46bb57e
--- /dev/null
+++ b/pcr-controller/temp_curve.h
@@ -0,0 +1,40 @@
+/*
+ * rPCR Teensy Controller Code
+ *
+ *
+ * Copyright (C) 2013-2014 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);
+void tcurve_setRepeatStartPosToLatestEntry(void);
+void tcurve_setRepeatEndPosToLatestEntry(void);
+uint8_t tcurve_isSet(void);
+uint8_t tcurve_hasFinished(void);
+uint16_t tcurve_getTimeElapsed(void);
+uint8_t tcurve_getRepeatsLeft(void);
+void tcurve_add(int16_t temp, uint16_t hold_for_s);
+int16_t tcurve_getTempToSet(int16_t current_temp, uint16_t time_elapsed);
+void tcurve_printCurve(uint8_t cmd);
+
+#endif