Software now supports breakout board

master
James Gao 2014-11-29 09:04:33 -08:00
rodzic eebe48d4d8
commit 01149be0ce
12 zmienionych plików z 501 dodań i 79 usunięć

Wyświetl plik

@ -1,5 +1,3 @@
#include <Bounce2.h>
#define PIN_IGNITE 10
#define PIN_STEP1 9
#define PIN_STEP2 8
@ -12,14 +10,16 @@
#define PIN_FLAME_D 1
#define PIN_REGLIMIT 5
#define STEP_SPEED 250//in steps per second
#define TEMP_UPDATE 100 //milliseconds
#define STEP_SPEED 275//in steps per second
#define TEMP_UPDATE 250 //milliseconds
#define MOTOR_TIMEOUT 5000 //milliseconds
#include <Stepper.h>
#include <Wire.h>
#include <SPI.h>
#include <Adafruit_MAX31855.h>
#include <ooPinChangeInt.h>
#include "pushbutton.h"
struct Status {
unsigned char ignite;
@ -37,14 +37,15 @@ const float step_interval = 1. / STEP_SPEED * 1000.; //milliseconds
//intermediate variables
Adafruit_MAX31855 thermo(PIN_TEMP_CS);
Stepper stepper(2048, PIN_STEP1, PIN_STEP3, PIN_STEP2, PIN_STEP4);
Bounce debouncer = Bounce();
unsigned int n_clicks = 0; //Number of full rotations
unsigned long stepper_target;
char i2c_command;
float next_step;
unsigned long next_temp;
unsigned char motor_active = false;
unsigned long stepper_target = 0;
unsigned int n_clicks = 0; //Number of full rotations
boolean limit_state = false;
unsigned long limit_last;
void setup() {
status.flame = false;
@ -59,13 +60,10 @@ void setup() {
//Set up regulator stepper
status.motor = 0;
stepper_target = 0;
//Set pullup for regulator limit
//setup regulator limit switch
pinMode(PIN_REGLIMIT, INPUT);
digitalWrite(PIN_REGLIMIT, HIGH);
debouncer.attach(PIN_REGLIMIT);
debouncer.interval(5);
//setup ignition mosfet
pinMode(PIN_IGNITE, OUTPUT);
@ -78,22 +76,27 @@ void setup() {
next_temp = millis() + TEMP_UPDATE;
}
int dir;
unsigned long now;
void loop() {
now = millis();
if (digitalRead(PIN_REGLIMIT) == LOW) {
if (limit_last == 0) {
limit_last = millis();
} else if ((millis() - limit_last) > 5) {
n_clicks += dir;
limit_last = 0;
}
}
if (stepper_target != status.motor && now > next_step) {
int dir = status.motor < stepper_target ? 1 : -1;
dir = status.motor < stepper_target ? 1 : -1;
stepper.step(dir);
boolean check = debouncer.update() && debouncer.read() == HIGH;
if (check) {
n_clicks += dir;
}
//If homing, continuing moving until switch is zero
if (stepper_target == 0 && check && n_clicks == 0) {
status.motor = 0;
//Limit switch tripped
if (stepper_target == 0) {
if (n_clicks == 0)
status.motor = 0;
} else {
status.motor += dir;
}
@ -121,16 +124,14 @@ void loop() {
void set_regulator(unsigned long pos) {
motor_active = true;
reglimit.setDir(status.motor < pos ? 1 : -1);
if (stepper_target == status.motor)
next_step = millis(); //Start stepping immediately
stepper_target = pos;
}
void update_temp() {
TempData temps;
thermo.readAll(temps);
status.main_temp = temps.celcius;
status.ambient = temps.internal;
thermo.readAll(status.main_temp, status.ambient);
}
void i2c_update() {
@ -166,10 +167,10 @@ void i2c_action(int nbytes) {
switch (i2c_command) {
case 'M':
set_regulator(*((unsigned long*) buffer));
set_regulator(*((unsigned int*) buffer));
break;
case 'I':
digitalWrite(PIN_TEMP_CS, buffer[0]);
digitalWrite(PIN_IGNITE, buffer[0]);
break;
}

Wyświetl plik

@ -0,0 +1,42 @@
class pushbutton : public CallBackInterface
{
public:
uint8_t n_clicks;
uint8_t pin;
unsigned int interval;
unsigned long last;
pushbutton (uint8_t _pin, unsigned int _interval): pin(_pin) , interval(_interval) {
dir = 0;
n_clicks = 0;
last = 0;
init();
state = digitalRead(pin);
};
void cbmethod() {
last = millis();
};
void update() {
if (last != 0 && (millis() - last) > interval) {
n_clicks += dir;
last = 0;
}
}
void setDir(int d) {
dir = d;
}
private:
int dir;
boolean state;
void init () {
pinMode(pin, INPUT);
digitalWrite(pin, HIGH);
PCintPort::attachInterrupt(pin, this, FALLING);
};
};

Wyświetl plik

@ -0,0 +1,172 @@
#define PIN_IGNITE 10
#define PIN_STEP1 9
#define PIN_STEP2 8
#define PIN_STEP3 7
#define PIN_STEP4 6
#define PIN_AUXTEMP A1
#define PIN_TEMP_CS 4
#define PIN_LOADCELL A3
#define PIN_FLAME_A A2
#define PIN_FLAME_D 1
#define PIN_REGLIMIT 5
#define STEP_SPEED 275//in steps per second
#define TEMP_UPDATE 250 //milliseconds
#define MOTOR_TIMEOUT 5000 //milliseconds
#define NO_PORTB_PINCHANGES
#define NO_PORTC_PINCHANGES
#define DISABLE_PCINT_MULTI_SERVICE
#include <Stepper.h>time.strftime('%Y-%m-%d_%I:%M%P.log')
#include <Wire.h>
#include <SPI.h>
#include <Adafruit_MAX31855.h>
#include <ooPinChangeInt.h>
#include "pushbutton.h"
struct Status {
unsigned char ignite;
unsigned char flame;
unsigned int motor;
float main_temp;
float ambient;
float weight;
float aux_temp[2];
} status;
uint8_t* status_data = (uint8_t*) &status;
const float step_interval = 1. / STEP_SPEED * 1000.; //milliseconds
//intermediate variables
Adafruit_MAX31855 thermo(PIN_TEMP_CS);
Stepper stepper(2048, PIN_STEP1, PIN_STEP3, PIN_STEP2, PIN_STEP4);
pushbutton reglimit = pushbutton(PIN_REGLIMIT, 5);
char i2c_command;
float next_step;
unsigned long next_temp;
unsigned char motor_active = false;
unsigned long stepper_target = 0;
unsigned int n_clicks = 0; //Number of full rotations
boolean limit_state = false;
unsigned long limit_last;
void setup() {
status.flame = false;
status.weight = 0.;
status.aux_temp[0] = 0.;
status.aux_temp[1] = 0.;
//Setup I2C
Wire.begin(0x08);
Wire.onRequest(i2c_update);
Wire.onReceive(i2c_action);
//Set up regulator stepper
status.motor = 0;
//setup ignition mosfet
pinMode(PIN_IGNITE, OUTPUT);
digitalWrite(PIN_IGNITE, LOW);
status.ignite = false;
//set initial temperature
delay(500);
update_temp();
next_temp = millis() + TEMP_UPDATE;
}
int dir;
unsigned long now;
void loop() {
now = millis();
reglimit.update();
if (stepper_target != status.motor && now > next_step) {
dir = status.motor < stepper_target ? 1 : -1;
stepper.step(dir);
//Limit switch tripped
if (stepper_target == 0) {
if (reglimit.n_clicks == 0)
status.motor = 0;
} else {
status.motor += dir;
}
next_step += step_interval;
}
//put motor to sleep after timeout
if (motor_active && (now - next_step) > MOTOR_TIMEOUT) {
digitalWrite(PIN_STEP1, LOW);
digitalWrite(PIN_STEP2, LOW);
digitalWrite(PIN_STEP3, LOW);
digitalWrite(PIN_STEP4, LOW);
motor_active = false;
}
//update temperature
if (now > next_temp) {
update_temp();
next_temp += TEMP_UPDATE;
}
//check flame status
}
void set_regulator(unsigned long pos) {
motor_active = true;
reglimit.setDir(status.motor < pos ? 1 : -1);
if (stepper_target == status.motor)
next_step = millis(); //Start stepping immediately
stepper_target = pos;
}
void update_temp() {
thermo.readAll(status.main_temp, status.ambient);
}
void i2c_update() {
//update temperatures
if (i2c_command == 'M') {
Wire.write((byte*) &(status.motor), 4);
} else if (i2c_command == 'I') {
Wire.write((byte*) &(status.ignite), 1);
} else if (i2c_command == 'T') {
Wire.write((byte*) &(status.main_temp), 4);
} else if (i2c_command == 'F') {
Wire.write((byte*) &(status.flame), 1);
} else {
Wire.write(status_data, sizeof(struct Status));
}
i2c_command = 0;
}
byte buffer[32];
void i2c_action(int nbytes) {
i2c_command = Wire.read();
int i = 0;
while (Wire.available()) {
buffer[i++] = Wire.read();
}
if (nbytes == 1) {
return; //Command already stored, no arguments
}
switch (i2c_command) {
case 'M':
set_regulator(*((unsigned int*) buffer));
break;
case 'I':
analogWrite(PIN_IGNITE, buffer[0]);
break;
}
i2c_command = 0;
}

Wyświetl plik

@ -0,0 +1,39 @@
#include "protocol.h"
char Comm::buffer[BUFFER_LENGTH+1];
int Comm::_nacts;
char Comm::_commands[MAX_ACTIONS];
char* (*Comm::_actions[MAX_ACTIONS])(int, char*);
char Comm::_current_cmd;
int Comm::_current_len;
Comm::Comm(int addr) {
Wire.begin(addr);
Wire.onReceive(_handle_request);
Wire.onRequest(_handle_response);
}
int Comm::action(char cmd, char* (*func)(int, char*)) {
if (_nacts >= MAX_ACTIONS)
return 1;
_actions[_nacts] = func;
return 0;
}
void Comm::_handle_request(int nbytes) {
_current_cmd = Wire.read();
_current_len = nbytes-1;
for (int i = 0; i < nbytes-1; i++) {
buffer[i] = Wire.read();
}
}
void Comm::_handle_response() {
for (int i = 0; i < MAX_ACTIONS; i++) {
if (_commands[i] == _current_cmd) {
_actions[i](_current_len, buffer);
}
}
Wire.write(buffer);
}

Wyświetl plik

@ -0,0 +1,25 @@
#ifndef PROTOCOL_H
#define PROTOCOL_H
#include "Wire.h"
#define MAX_ACTIONS 16
class Comm {
private:
static char buffer[BUFFER_LENGTH+1];
static int _nacts;
static char _commands[MAX_ACTIONS];
static char* (*_actions[MAX_ACTIONS])(int, char*);
static char _current_cmd;
static int _current_len;
static void _handle_request(int);
static void _handle_response(void);
public:
Comm(int addr);
int action(char, char* (*)(int, char*));
};
#endif //PROTOCOL_H

Wyświetl plik

@ -0,0 +1,42 @@
class pushbutton : public CallBackInterface
{
public:
uint8_t n_clicks;
uint8_t pin;
unsigned int interval;
unsigned long last;
pushbutton (uint8_t _pin, unsigned int _interval): pin(_pin) , interval(_interval) {
dir = 0;
n_clicks = 0;
last = 0;
init();
state = digitalRead(pin);
};
void cbmethod() {
last = millis();
};
void update() {
if (last != 0 && (millis() - last) > interval) {
n_clicks += dir;
last = 0;
}
}
void setDir(int d) {
dir = d;
}
private:
int dir;
boolean state;
void init () {
pinMode(pin, INPUT);
digitalWrite(pin, HIGH);
PCintPort::attachInterrupt(pin, this, FALLING);
};
};

58
kiln/breakout.py 100644
Wyświetl plik

@ -0,0 +1,58 @@
import smbus
import struct
from collections import namedtuple
Status = namedtuple('Status', 'ignite flame motor main_temp ambient weight aux_temp0 aux_temp1')
class Breakout(object):
fmt = struct.Struct('<BBH5f')
def __init__(self, addr, bus=1):
self.bus = smbus.SMBus(1)
self.addr = addr
@property
def status(self):
while True:
try:
chars = map(chr, self.bus.read_i2c_block_data(self.addr, 0, self.fmt.size))
return Status._make(self.fmt.unpack(''.join(chars)))
except IOError:
#ignore IOError due to i2c timeout
pass
def __repr__(self):
return repr(self.status)
def _get_cmd(self, cmd, fmt='f'):
s = struct.Struct('<'+fmt)
while True:
try:
data = self.bus.read_i2c_block_data(self.addr, ord(cmd), s.size)
return s.unpack(''.join(map(chr, data)))[0]
except IOError:
#ignore IOError due to i2c timeout
pass
def _set_cmd(self, cmd, value, fmt='f'):
out = map(ord, struct.pack('<'+fmt, value))
self.bus.write_i2c_block_data(self.addr, ord(cmd), out)
@property
def motor(self):
return self._get_cmd('M', fmt='H')
@motor.setter
def motor(self, pos):
self._set_cmd('M', pos, fmt='H')
@property
def temperature(self):
return self._get_cmd('T', fmt='f')
@property
def ignite(self):
return self._get_cmd('I', fmt='B')
@ignite.setter
def ignite(self, output):
self._set_cmd('I', output, fmt='B')

Wyświetl plik

@ -1,41 +0,0 @@
import smbus
import struct
from collections import namedtuple
Status = namedtuple('Status', 'ignite flame motor main_temp ambient weight aux_temp0 aux_temp1')
class Kiln(object):
fmt = struct.Struct('<2BH5f')
def __init__(self, addr, bus=1):
self.bus = smbus.SMBus(1)
self.addr = addr
@property
def status(self):
chars = map(chr, self.bus.read_i2c_block_data(self.addr, 0, self.fmt.size))
return Status._make(self.fmt.unpack(''.join(chars)))
def __repr__(self):
return repr(self.status)
@property
def motor(self):
return self.status.motor
@motor.setter
def motor(self, pos):
out = map(ord, struct.pack('I',pos))
self.bus.write_i2c_block_data(self.addr,ord('M'), out)
@property
def temperature(self):
data = self.bus.read_i2c_block_data(self.addr,ord('T'), 4)
return struct.unpack('<f', ''.join(map(chr, data)))[0]
@property
def ignite(self):
return self.status.ignite
@ignite.setter
def ignite(self, output):
self.bus.write_i2c_block_data(self.addr,ord('I'), [int(output)])

Wyświetl plik

@ -11,6 +11,35 @@ import PID
logger = logging.getLogger("kiln.manager")
class TempLog(object):
def __init__(self, history, interval=60, suffix=""): #save data every 60 seconds
import paths
self.history = history
fname = time.strftime('%Y-%m-%d_%I:%M%P')
if len(suffix) > 0:
suffix = "_"+suffix
self.fname = os.path.join(paths.log_path, fname+suffix+".log")
with open(self.fname, 'w') as fp:
fp.write("time\ttemp\n")
for time, temp in history:
fp.write("%f\t%f\n"%(time, temp))
self.next = time.time() + interval
self.interval = interval
self._buffer = []
def __iter__(self):
return iter(self.history)
def append(self, data):
self.history.append(data)
self._buffer.append(data)
if time.time() > self.next:
with open(self.fname, 'a') as fp:
for time, temp in self._buffer:
fp.write("%f\t%f\n"%(time, temp))
self._buffer = []
self.next = time.time() + self.interval
class Manager(threading.Thread):
def __init__(self, start=states.Idle, simulate=False):
"""
@ -18,12 +47,13 @@ class Manager(threading.Thread):
"""
super(Manager, self).__init__()
self._send = None
self.regulator = stepper.Regulator(simulate=simulate)
if simulate:
self.regulator = stepper.Regulator(simulate=simulate)
self.therm = thermo.Simulate(regulator=self.regulator)
else:
self.therm = thermo.MAX31850()
self.regulator = stepper.Breakout(0x08)
self.therm = thermo.Breakout(0x08)
self.state = start(self)
self.state_change = threading.Event()
@ -75,8 +105,8 @@ class Manager(threading.Thread):
class Profile(threading.Thread):
"""Performs the PID loop required for feedback control"""
def __init__(self, schedule, therm, regulator, interval=5, start_time=None, callback=None,
Kp=.025, Ki=.01, Kd=.005):
def __init__(self, schedule, therm, regulator, interval=1, start_time=None, callback=None,
Kp=.025, Ki=.01, Kd=.001):
self.schedule = schedule
self.therm = therm
self.regulator = regulator
@ -115,7 +145,7 @@ class Profile(threading.Thread):
setpoint = frac * (temp1 - temp0) + temp0
self.pid.setPoint(setpoint)
temp = self.thermocouple.temperature
temp = self.therm.temperature
pid_out = self.pid.update(temp)
if pid_out < 0: pid_out = 0
if pid_out > 1: pid_out = 1

Wyświetl plik

@ -19,7 +19,7 @@ class State(object):
class Idle(State):
def __init__(self, manager):
super(Idle, self).__init__(manager)
self.history = deque(maxlen=1024) #about 10 minutes worth
self.history = deque(maxlen=2400) #about 10 minutes worth, 4 samples / sec * 60 sec / min * 10 min
def ignite(self):
_ignite(self.parent.regulator, self.parent.notify)
@ -37,7 +37,7 @@ class Idle(State):
class Lit(State):
def __init__(self, parent, history):
super(Lit, self).__init__(parent)
self.history = deque(history)
self.history = manager.TempLog(history)
def set(self, value):
try:
@ -67,7 +67,11 @@ class Cooling(State):
ts = self.parent.therm.get()
self.history.append(ts)
if ts.temp < 50:
#TODO: save temperature log somewhere
# Direction logged by TempLog
# fname = time.strftime('%Y-%m-%d_%I:%M%P.log')
# with open(os.path.join(paths.log_path, fname), 'w') as fp:
# for time, temp in self.history:
# fp.write("%s\t%s\n"%time, temp)
return Idle
return dict(type="temperature", time=ts.time, temp=ts.temp)

Wyświetl plik

@ -241,4 +241,41 @@ class Regulator(threading.Thread):
def run(self):
"""Check the status of the flame sensor"""
#since the flame sensor does not yet exist, we'll save this for later
pass
pass
class Breakout(object):
def __init__(self, addr, maxsteps=4500, minsteps=2500):
import breakout
self.device = breakout.Breakout(addr)
self.min = minsteps
self.max = maxsteps
def exit():
if self.output != 0:
self.off()
atexit.register(exit)
def ignite(self, start=2800, delay=10):
self.device.ignite = 255
time.sleep(delay)
self.device.motor = start
time.sleep(5)
self.device.motor = self.min
self.device.ignite = 127
@property
def output(self):
out = (self.device.motor - self.min) / float(self.max - self.min)
if out < 0:
return -1
return out
def set(self, value):
if self.device.motor == 0:
raise ValueError('Must ignite first')
if not 0 <= value <= 1:
raise ValueError('Must give value between 0 and 1')
self.device.motor = int((self.max - self.min)*value + self.min)
def off(self):
self.device.motor = 0

Wyświetl plik

@ -54,13 +54,13 @@ class MAX31850(object):
return tempsample(self.last, sum(self.history) / float(len(self.history)))
class Simulate(object):
def __init__(self, regulator, smooth_window=4):
def __init__(self, regulator, smooth_window=8):
self.regulator = regulator
self.history = deque(maxlen=smooth_window)
self.last = None
def _read_temp(self):
time.sleep(.8)
time.sleep(.25)
return max([self.regulator.output, 0]) * 1000. + 15+random.gauss(0,.2)
def get(self):
@ -75,6 +75,19 @@ class Simulate(object):
return tempsample(self.last, sum(self.history) / float(len(self.history)))
class Breakout(object):
def __init__(self, addr):
import breakout
self.device = breakout.Breakout(addr)
def get(self):
time.sleep(.25)
return self.device.temperature
@property
def temperature(self):
return self.device.temperature
class Monitor(threading.Thread):
def __init__(self, cls=MAX31850, **kwargs):
self.therm = cls(**kwargs)