kopia lustrzana https://github.com/jamesgao/kiln_controller
Working profile running, events still need work
rodzic
42af7b85aa
commit
79e1403f03
|
@ -18,7 +18,7 @@
|
||||||
#define NO_PORTC_PINCHANGES
|
#define NO_PORTC_PINCHANGES
|
||||||
#define DISABLE_PCINT_MULTI_SERVICE
|
#define DISABLE_PCINT_MULTI_SERVICE
|
||||||
|
|
||||||
#include <Stepper.h>time.strftime('%Y-%m-%d_%I:%M%P.log')
|
#include <Stepper.h>
|
||||||
#include <Wire.h>
|
#include <Wire.h>
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
#include <Adafruit_MAX31855.h>
|
#include <Adafruit_MAX31855.h>
|
||||||
|
@ -48,7 +48,7 @@ float next_step;
|
||||||
unsigned long next_temp;
|
unsigned long next_temp;
|
||||||
unsigned char motor_active = false;
|
unsigned char motor_active = false;
|
||||||
unsigned long stepper_target = 0;
|
unsigned long stepper_target = 0;
|
||||||
unsigned int n_clicks = 0; //Number of full rotations
|
int n_clicks = 0; //Number of full rotations
|
||||||
boolean limit_state = false;
|
boolean limit_state = false;
|
||||||
unsigned long limit_last;
|
unsigned long limit_last;
|
||||||
|
|
||||||
|
@ -165,6 +165,7 @@ void i2c_action(int nbytes) {
|
||||||
break;
|
break;
|
||||||
case 'I':
|
case 'I':
|
||||||
analogWrite(PIN_IGNITE, buffer[0]);
|
analogWrite(PIN_IGNITE, buffer[0]);
|
||||||
|
status.ignite = buffer[0];
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
class pushbutton : public CallBackInterface
|
class pushbutton : public CallBackInterface
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
uint8_t n_clicks;
|
int n_clicks;
|
||||||
uint8_t pin;
|
uint8_t pin;
|
||||||
unsigned int interval;
|
unsigned int interval;
|
||||||
unsigned long last;
|
unsigned long last;
|
||||||
|
@ -11,8 +11,6 @@ class pushbutton : public CallBackInterface
|
||||||
n_clicks = 0;
|
n_clicks = 0;
|
||||||
last = 0;
|
last = 0;
|
||||||
init();
|
init();
|
||||||
state = digitalRead(pin);
|
|
||||||
|
|
||||||
};
|
};
|
||||||
void cbmethod() {
|
void cbmethod() {
|
||||||
last = millis();
|
last = millis();
|
||||||
|
@ -31,12 +29,11 @@ class pushbutton : public CallBackInterface
|
||||||
|
|
||||||
private:
|
private:
|
||||||
int dir;
|
int dir;
|
||||||
boolean state;
|
|
||||||
|
|
||||||
void init () {
|
void init () {
|
||||||
pinMode(pin, INPUT);
|
pinMode(pin, INPUT);
|
||||||
digitalWrite(pin, HIGH);
|
digitalWrite(pin, HIGH);
|
||||||
PCintPort::attachInterrupt(pin, this, FALLING);
|
PCintPort::attachInterrupt(pin, this, CHANGE);
|
||||||
};
|
};
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -10,7 +10,8 @@ import logging
|
||||||
import states
|
import states
|
||||||
import PID
|
import PID
|
||||||
|
|
||||||
logger = logging.getLogger("kiln.manager")
|
logger = logging.getLogger(__name__)
|
||||||
|
logger.setLevel(logging.INFO)
|
||||||
|
|
||||||
class TempLog(object):
|
class TempLog(object):
|
||||||
def __init__(self, history, interval=60, suffix=""): #save data every 60 seconds
|
def __init__(self, history, interval=60, suffix=""): #save data every 60 seconds
|
||||||
|
@ -71,7 +72,7 @@ class Manager(threading.Thread):
|
||||||
def __getattr__(self, name):
|
def __getattr__(self, name):
|
||||||
"""Mutates the manager to return State actions
|
"""Mutates the manager to return State actions
|
||||||
If the requested attribute is a function, wrap the function
|
If the requested attribute is a function, wrap the function
|
||||||
such that returned objects which are States indicate a state change
|
such that returned obejcts which are States indicate a state change
|
||||||
"""
|
"""
|
||||||
attr = getattr(self.state, name)
|
attr = getattr(self.state, name)
|
||||||
if hasattr(attr, "__call__"):
|
if hasattr(attr, "__call__"):
|
||||||
|
@ -86,10 +87,12 @@ class Manager(threading.Thread):
|
||||||
self.state = output(self)
|
self.state = output(self)
|
||||||
self.state_change.set()
|
self.state_change.set()
|
||||||
self.notify(dict(type="state", state=output.__name__))
|
self.notify(dict(type="state", state=output.__name__))
|
||||||
|
logger.info("Switching to state '%s'"%output.__name__)
|
||||||
elif isinstance(output, tuple) and issubclass(output[0], states.State):
|
elif isinstance(output, tuple) and issubclass(output[0], states.State):
|
||||||
newstate, kwargs = output
|
newstate, kwargs = output
|
||||||
self.state = newstate(self, **kwargs)
|
self.state = newstate(self, **kwargs)
|
||||||
self.notify(dict(type="state", state=newstate.__name__))
|
self.notify(dict(type="state", state=newstate.__name__))
|
||||||
|
logger.info("Switching to state '%s'"%newstate.__name__)
|
||||||
elif isinstance(output, dict) and "type" in output:
|
elif isinstance(output, dict) and "type" in output:
|
||||||
self.notify(output)
|
self.notify(output)
|
||||||
elif output is not None:
|
elif output is not None:
|
||||||
|
@ -103,11 +106,13 @@ class Manager(threading.Thread):
|
||||||
self.running = False
|
self.running = False
|
||||||
self.state_change.set()
|
self.state_change.set()
|
||||||
|
|
||||||
|
|
||||||
class Profile(threading.Thread):
|
class Profile(threading.Thread):
|
||||||
"""Performs the PID loop required for feedback control"""
|
"""Performs the PID loop required for feedback control"""
|
||||||
def __init__(self, schedule, therm, regulator, interval=1, start_time=None, callback=None,
|
def __init__(self, schedule, therm, regulator, interval=1, start_time=None, callback=None,
|
||||||
Kp=.025, Ki=.01, Kd=.001):
|
Kp=.025, Ki=.01, Kd=.001):
|
||||||
|
super(Profile, self).__init__()
|
||||||
|
self.daemon = True
|
||||||
|
|
||||||
self.schedule = schedule
|
self.schedule = schedule
|
||||||
self.therm = therm
|
self.therm = therm
|
||||||
self.regulator = regulator
|
self.regulator = regulator
|
||||||
|
@ -146,7 +151,7 @@ class Profile(threading.Thread):
|
||||||
setpoint = frac * (temp1 - temp0) + temp0
|
setpoint = frac * (temp1 - temp0) + temp0
|
||||||
self.pid.setPoint(setpoint)
|
self.pid.setPoint(setpoint)
|
||||||
|
|
||||||
temp = self.therm.temperature
|
temp = self.therm.temperature.temp
|
||||||
pid_out = self.pid.update(temp)
|
pid_out = self.pid.update(temp)
|
||||||
if pid_out < 0: pid_out = 0
|
if pid_out < 0: pid_out = 0
|
||||||
if pid_out > 1: pid_out = 1
|
if pid_out > 1: pid_out = 1
|
||||||
|
|
|
@ -35,8 +35,10 @@ class MainHandler(ManagerHandler):
|
||||||
files = os.listdir(paths.profile_path)
|
files = os.listdir(paths.profile_path)
|
||||||
fixname = lambda x: cone_symbol.sub(r'Δ\1', os.path.splitext(x)[0].replace("_", " "))
|
fixname = lambda x: cone_symbol.sub(r'Δ\1', os.path.splitext(x)[0].replace("_", " "))
|
||||||
profiles = dict((fname, fixname(fname)) for fname in files)
|
profiles = dict((fname, fixname(fname)) for fname in files)
|
||||||
|
|
||||||
return self.render(os.path.join(paths.html_templates, "main.html"),
|
return self.render(os.path.join(paths.html_templates, "main.html"),
|
||||||
state=self.manager.state.__class__.__name__,
|
state=self.manager.state.__class__.__name__,
|
||||||
|
state_data=json.dumps(self.manager.state.status),
|
||||||
profiles=profiles,
|
profiles=profiles,
|
||||||
)
|
)
|
||||||
|
|
||||||
|
@ -129,7 +131,7 @@ class WebApp(object):
|
||||||
if __name__ == "__main__":
|
if __name__ == "__main__":
|
||||||
try:
|
try:
|
||||||
import manager
|
import manager
|
||||||
kiln = manager.Manager(simulate=False)
|
kiln = manager.Manager(simulate=True)
|
||||||
app = WebApp(kiln)
|
app = WebApp(kiln)
|
||||||
kiln._send = app.send
|
kiln._send = app.send
|
||||||
|
|
||||||
|
|
|
@ -1,6 +1,7 @@
|
||||||
"""Based on the pattern provided here:
|
"""Based on the pattern provided here:
|
||||||
http://python-3-patterns-idioms-test.readthedocs.org/en/latest/StateMachine.html
|
http://python-3-patterns-idioms-test.readthedocs.org/en/latest/StateMachine.html
|
||||||
"""
|
"""
|
||||||
|
import json
|
||||||
import time
|
import time
|
||||||
import traceback
|
import traceback
|
||||||
import manager
|
import manager
|
||||||
|
@ -10,6 +11,10 @@ class State(object):
|
||||||
def __init__(self, manager):
|
def __init__(self, manager):
|
||||||
self.parent = manager
|
self.parent = manager
|
||||||
|
|
||||||
|
@property
|
||||||
|
def status(self):
|
||||||
|
return dict()
|
||||||
|
|
||||||
def run(self):
|
def run(self):
|
||||||
"""Action that must be continuously run while in this state"""
|
"""Action that must be continuously run while in this state"""
|
||||||
ts = self.parent.therm.get()
|
ts = self.parent.therm.get()
|
||||||
|
@ -25,7 +30,7 @@ class Idle(State):
|
||||||
_ignite(self.parent.regulator, self.parent.notify)
|
_ignite(self.parent.regulator, self.parent.notify)
|
||||||
return Lit, dict(history=self.history)
|
return Lit, dict(history=self.history)
|
||||||
|
|
||||||
def start(self, schedule, start_time=None, interval=5):
|
def start_profile(self, schedule, start_time=None, interval=5):
|
||||||
_ignite(self.parent.regulator, self.parent.notify)
|
_ignite(self.parent.regulator, self.parent.notify)
|
||||||
kwargs = dict(history=self.history,
|
kwargs = dict(history=self.history,
|
||||||
schedule=json.loads(schedule),
|
schedule=json.loads(schedule),
|
||||||
|
@ -46,7 +51,7 @@ class Lit(State):
|
||||||
except:
|
except:
|
||||||
return dict(type="error", msg=traceback.format_exc())
|
return dict(type="error", msg=traceback.format_exc())
|
||||||
|
|
||||||
def start(self, schedule, start_time=None, interval=5):
|
def start_profile(self, schedule, start_time=None, interval=5):
|
||||||
kwargs = dict(history=self.history,
|
kwargs = dict(history=self.history,
|
||||||
schedule=json.loads(schedule),
|
schedule=json.loads(schedule),
|
||||||
start_time=float(start_time),
|
start_time=float(start_time),
|
||||||
|
@ -54,7 +59,7 @@ class Lit(State):
|
||||||
)
|
)
|
||||||
return Running, kwargs
|
return Running, kwargs
|
||||||
|
|
||||||
def stop(self):
|
def shutoff(self):
|
||||||
_shutoff(self.parent.regulator, self.parent.notify)
|
_shutoff(self.parent.regulator, self.parent.notify)
|
||||||
return Cooling, dict(history=self.history)
|
return Cooling, dict(history=self.history)
|
||||||
|
|
||||||
|
@ -79,7 +84,7 @@ class Cooling(State):
|
||||||
_ignite(self.parent.regulator, self.parent.notify)
|
_ignite(self.parent.regulator, self.parent.notify)
|
||||||
return Lit, dict(history=self.history)
|
return Lit, dict(history=self.history)
|
||||||
|
|
||||||
def start(self, schedule, start_time=None, interval=5):
|
def start_profile(self, schedule, start_time=None, interval=5):
|
||||||
_ignite(self.parent.regulator, self.parent.notify)
|
_ignite(self.parent.regulator, self.parent.notify)
|
||||||
kwargs = dict(history=self.history,
|
kwargs = dict(history=self.history,
|
||||||
schedule=json.loads(schedule),
|
schedule=json.loads(schedule),
|
||||||
|
@ -91,11 +96,15 @@ class Cooling(State):
|
||||||
class Running(State):
|
class Running(State):
|
||||||
def __init__(self, parent, history, start_time=None, **kwargs):
|
def __init__(self, parent, history, start_time=None, **kwargs):
|
||||||
super(Running, self).__init__(parent)
|
super(Running, self).__init__(parent)
|
||||||
self.start_time = start_time
|
|
||||||
self.profile = manager.Profile(therm=self.parent.therm, regulator=self.parent.regulator,
|
self.profile = manager.Profile(therm=self.parent.therm, regulator=self.parent.regulator,
|
||||||
callback=self._notify, start_time=start_time, **kwargs)
|
callback=self._notify, start_time=start_time, **kwargs)
|
||||||
|
self.start_time = self.profile.start_time
|
||||||
self.history = history
|
self.history = history
|
||||||
|
|
||||||
|
@property
|
||||||
|
def status(self):
|
||||||
|
return dict(start_time=self.start_time, schedule=self.profile.schedule)
|
||||||
|
|
||||||
def _notify(self, therm, setpoint, out):
|
def _notify(self, therm, setpoint, out):
|
||||||
self.parent.notify(dict(
|
self.parent.notify(dict(
|
||||||
type="profile",
|
type="profile",
|
||||||
|
@ -107,7 +116,8 @@ class Running(State):
|
||||||
|
|
||||||
def run(self):
|
def run(self):
|
||||||
if self.profile.completed:
|
if self.profile.completed:
|
||||||
self.parent.notify(dict(type="profile",status="complete"))
|
#self.parent.notify(dict(type="profile",status="complete"))
|
||||||
|
print "Profile complete!"
|
||||||
_shutoff(self.parent.regulator, self.parent.notify)
|
_shutoff(self.parent.regulator, self.parent.notify)
|
||||||
return Cooling, dict(history=self.history)
|
return Cooling, dict(history=self.history)
|
||||||
|
|
||||||
|
@ -117,11 +127,13 @@ class Running(State):
|
||||||
self.profile.stop()
|
self.profile.stop()
|
||||||
return Lit, dict(history=self.history)
|
return Lit, dict(history=self.history)
|
||||||
|
|
||||||
def stop(self):
|
def stop_profile(self):
|
||||||
self.profile.stop()
|
self.profile.stop()
|
||||||
_shutoff(self.parent.regulator, self.parent.notify)
|
_shutoff(self.parent.regulator, self.parent.notify)
|
||||||
return Cooling, dict(history=self.history)
|
return Cooling, dict(history=self.history)
|
||||||
|
|
||||||
|
def shutoff(self):
|
||||||
|
return self.stop_profile()
|
||||||
|
|
||||||
def _ignite(regulator, notify):
|
def _ignite(regulator, notify):
|
||||||
try:
|
try:
|
||||||
|
|
|
@ -100,8 +100,8 @@ var tempgraph = (function(module) {
|
||||||
return {x:new Date(d.time*1000), y:this.scalefunc.scale(d.temp)};
|
return {x:new Date(d.time*1000), y:this.scalefunc.scale(d.temp)};
|
||||||
}
|
}
|
||||||
|
|
||||||
module.Monitor.prototype.setState = function(name) {
|
module.Monitor.prototype.setState = function(name, data) {
|
||||||
if (name == "Lit") {
|
if (name == "Lit" || name =="Running") {
|
||||||
$("#ignite_button").addClass("disabled");
|
$("#ignite_button").addClass("disabled");
|
||||||
$("#current_output").removeAttr("disabled");
|
$("#current_output").removeAttr("disabled");
|
||||||
$("#stop_button").removeClass("disabled");
|
$("#stop_button").removeClass("disabled");
|
||||||
|
@ -113,8 +113,14 @@ var tempgraph = (function(module) {
|
||||||
$("#stop_button").addClass("disabled");
|
$("#stop_button").addClass("disabled");
|
||||||
$("#stop_button_navbar").addClass("hidden disabled");
|
$("#stop_button_navbar").addClass("hidden disabled");
|
||||||
$("#profile_select").removeClass("disabled");
|
$("#profile_select").removeClass("disabled");
|
||||||
} else if (name == "Profile") {
|
}
|
||||||
|
if (name == "Running") {
|
||||||
|
if (data !== undefined) {
|
||||||
|
this.setProfile(data.schedule, new Date(data.start_time*1000));
|
||||||
|
}
|
||||||
|
this.profile.setState(true);
|
||||||
|
} else if (this.profile === undefined) {
|
||||||
|
this.profile.setState(false);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
module.Monitor.prototype._bindUI = function() {
|
module.Monitor.prototype._bindUI = function() {
|
||||||
|
@ -134,7 +140,7 @@ var tempgraph = (function(module) {
|
||||||
|
|
||||||
$("#stop_button, #stop_button_navbar").click(function() {
|
$("#stop_button, #stop_button_navbar").click(function() {
|
||||||
this._disable_all();
|
this._disable_all();
|
||||||
$.getJSON("/do/stop", function(data) {
|
$.getJSON("/do/shutoff", function(data) {
|
||||||
if (data.type == "error")
|
if (data.type == "error")
|
||||||
alert(data.msg, data.error);
|
alert(data.msg, data.error);
|
||||||
else if (data.type == "success") {
|
else if (data.type == "success") {
|
||||||
|
|
|
@ -1,11 +1,10 @@
|
||||||
var tempgraph = (function(module) {
|
var tempgraph = (function(module) {
|
||||||
module.Profile = function(graph, scale, schedule, start_time, running) {
|
module.Profile = function(graph, scale, schedule, start_time) {
|
||||||
var end = schedule[schedule.length-1][0];
|
var end = schedule[schedule.length-1][0];
|
||||||
this.length = end;
|
this.length = end;
|
||||||
this.time_total = juration.stringify(end);
|
this.time_total = juration.stringify(end);
|
||||||
this.time_start = start_time;
|
this.time_start = start_time;
|
||||||
this.schedule = schedule;
|
this.schedule = schedule;
|
||||||
this.running = running === undefined ? false : running;
|
|
||||||
|
|
||||||
this.graph = graph;
|
this.graph = graph;
|
||||||
this.scalefunc = scale;
|
this.scalefunc = scale;
|
||||||
|
@ -291,7 +290,6 @@ var tempgraph = (function(module) {
|
||||||
}
|
}
|
||||||
module.Profile.prototype.setState = function(running) {
|
module.Profile.prototype.setState = function(running) {
|
||||||
this.running = running === undefined ? this.running : running;
|
this.running = running === undefined ? this.running : running;
|
||||||
console.log("Set State: ", this.running);
|
|
||||||
if (this.running) {
|
if (this.running) {
|
||||||
this.line.marker.on("dblclick.profile", null);
|
this.line.marker.on("dblclick.profile", null);
|
||||||
this.graph.pane.on("dblclick.profile", null);
|
this.graph.pane.on("dblclick.profile", null);
|
||||||
|
@ -325,14 +323,22 @@ var tempgraph = (function(module) {
|
||||||
}
|
}
|
||||||
module.Profile.prototype.start = function() {
|
module.Profile.prototype.start = function() {
|
||||||
$("#profile_actions .btn-primary").addClass("disabled");
|
$("#profile_actions .btn-primary").addClass("disabled");
|
||||||
|
var start_time = this.time_start instanceof Date ? this.time_start : new Date();
|
||||||
//TODO: ajax query
|
var params = {
|
||||||
//This should be done by the query
|
schedule:JSON.stringify(this.schedule),
|
||||||
this.setState(true);
|
start_time:start_time.getTime() / 1000.,
|
||||||
if (!(this.time_start instanceof Date))
|
interval:1,
|
||||||
this.time_start = new Date();
|
};
|
||||||
|
$.post("/do/start_profile", params, function(resp){
|
||||||
|
var obj = JSON.parse(resp);
|
||||||
|
if (obj.type == "error") {
|
||||||
|
alert(obj.msg);
|
||||||
|
} else {
|
||||||
|
this.setState(true);
|
||||||
|
this.time_start = start_time;
|
||||||
|
}
|
||||||
|
}.bind(this));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
return module;
|
return module;
|
||||||
}(tempgraph || {}));
|
}(tempgraph || {}));
|
||||||
|
|
|
@ -152,7 +152,7 @@ class StepperSim(object):
|
||||||
time.sleep(1)
|
time.sleep(1)
|
||||||
|
|
||||||
def stop(self):
|
def stop(self):
|
||||||
print "stopping"
|
print "stopping simulated regulator"
|
||||||
|
|
||||||
class Regulator(threading.Thread):
|
class Regulator(threading.Thread):
|
||||||
def __init__(self, maxsteps=4500, minsteps=2480, speed=150, ignite_pin=None, flame_pin=None, simulate=False):
|
def __init__(self, maxsteps=4500, minsteps=2480, speed=150, ignite_pin=None, flame_pin=None, simulate=False):
|
||||||
|
@ -216,8 +216,8 @@ class Regulator(threading.Thread):
|
||||||
|
|
||||||
def off(self, block=True):
|
def off(self, block=True):
|
||||||
logger.info("Shutting off gas")
|
logger.info("Shutting off gas")
|
||||||
#self.stepper.step(-self.current, self.speed, block=block)
|
self.stepper.step(-self.current, self.speed, block=block)
|
||||||
self.stepper.home()
|
#self.stepper.home()
|
||||||
self.current = 0
|
self.current = 0
|
||||||
|
|
||||||
def set(self, value, block=False):
|
def set(self, value, block=False):
|
||||||
|
@ -251,11 +251,12 @@ class Breakout(object):
|
||||||
self.max = maxsteps
|
self.max = maxsteps
|
||||||
|
|
||||||
def exit():
|
def exit():
|
||||||
if self.output != 0:
|
if self.device.motor != 0:
|
||||||
self.off()
|
self.off()
|
||||||
atexit.register(exit)
|
atexit.register(exit)
|
||||||
|
|
||||||
def ignite(self, start=2800, delay=10):
|
def ignite(self, start=2800, delay=10):
|
||||||
|
logger.info("Igniting system")
|
||||||
self.device.ignite = 255
|
self.device.ignite = 255
|
||||||
time.sleep(delay)
|
time.sleep(delay)
|
||||||
self.device.motor = start
|
self.device.motor = start
|
||||||
|
@ -279,3 +280,4 @@ class Breakout(object):
|
||||||
|
|
||||||
def off(self):
|
def off(self):
|
||||||
self.device.motor = 0
|
self.device.motor = 0
|
||||||
|
logger.info("Shutting off regulator")
|
|
@ -140,8 +140,7 @@
|
||||||
var monitor;
|
var monitor;
|
||||||
d3.json("temperature.json", function(error, data) {
|
d3.json("temperature.json", function(error, data) {
|
||||||
monitor = new tempgraph.Monitor(data);
|
monitor = new tempgraph.Monitor(data);
|
||||||
monitor.setState("{{ state }}");
|
monitor.setState("{{ state }}",{% autoescape None %} JSON.parse('{{ state_data }}'));
|
||||||
|
|
||||||
});
|
});
|
||||||
</script>
|
</script>
|
||||||
</body>
|
</body>
|
||||||
|
|
|
@ -54,7 +54,7 @@ class MAX31850(object):
|
||||||
return tempsample(self.last, sum(self.history) / float(len(self.history)))
|
return tempsample(self.last, sum(self.history) / float(len(self.history)))
|
||||||
|
|
||||||
class Simulate(object):
|
class Simulate(object):
|
||||||
def __init__(self, regulator, smooth_window=8):
|
def __init__(self, regulator, smooth_window=120):
|
||||||
self.regulator = regulator
|
self.regulator = regulator
|
||||||
self.history = deque(maxlen=smooth_window)
|
self.history = deque(maxlen=smooth_window)
|
||||||
self.last = None
|
self.last = None
|
||||||
|
|
|
@ -1,4 +1,4 @@
|
||||||
use <../lib/utils.scad>;
|
use <utils.scad>;
|
||||||
use <../lib/28byj.scad>;
|
use <../lib/28byj.scad>;
|
||||||
|
|
||||||
thick = 4;
|
thick = 4;
|
||||||
|
@ -44,8 +44,8 @@ module holder() {
|
||||||
|
|
||||||
module slot(length) {
|
module slot(length) {
|
||||||
hull() {
|
hull() {
|
||||||
cylinder(r=1, h=6);
|
cylinder(r=1.5, h=6, $fn=16);
|
||||||
translate([length,0]) cylinder(r=1, h=6);
|
translate([length,0]) cylinder(r=1.5, h=6, $fn=16);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -61,16 +61,16 @@ module holder() {
|
||||||
//switch tab
|
//switch tab
|
||||||
intersection() {
|
intersection() {
|
||||||
translate([0,0,-3.3-thick]) scale([1, 1.4]) difference() {
|
translate([0,0,-3.3-thick]) scale([1, 1.4]) difference() {
|
||||||
cylinder(r=36+thick, h=16+34+3, $fn=128);
|
cylinder(r=36+10+thick, h=16+34+3, $fn=128);
|
||||||
translate([0,0,-1]) cylinder(r=36, h=16+32+3-2,$fn=128);
|
translate([0,0,16]) cylinder(r=36+10, h=32+3-2,$fn=128);
|
||||||
}
|
}
|
||||||
translate([36+thick-20, -width/2, -3.3-thick]) cube([50, 20, 16+32+4]);
|
translate([36+thick-15, -width/2, -3.3-thick]) cube([50, 20, 16+32+4]);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
//Screw slots for switch
|
//Screw slots for switch
|
||||||
translate([20,-width/2+10-9.5/2, -3.3-thick+16+32-1]) {
|
translate([25,-width/2+10-9.5/2, -3.3-thick+16+32-1]) {
|
||||||
translate([3,0]) slot(5);
|
translate([3,0]) slot(10);
|
||||||
translate([3,9.5]) slot(5);
|
translate([3,9.5]) slot(10);
|
||||||
}
|
}
|
||||||
|
|
||||||
//Slot for wire to ensure no gear tangling
|
//Slot for wire to ensure no gear tangling
|
||||||
|
|
Plik diff jest za duży
Load Diff
Ładowanie…
Reference in New Issue