-
Notifications
You must be signed in to change notification settings - Fork 6
Expand file tree
/
Copy pathDomeShutter.ino
More file actions
233 lines (193 loc) · 5.92 KB
/
DomeShutter.ino
File metadata and controls
233 lines (193 loc) · 5.92 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
/*******************************************************************************
ArduinoDomeShutter
Shutter controller for an astronomical dome using Arduino
The MIT License
Copyright (C) 2017 Juan Menendez <[email protected]>
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
*******************************************************************************/
#include <avr/wdt.h>
#include "MonsterMotorShield.h"
#include "SerialCommand.h"
#include "shutter.h"
// Pin definitions
#define LED_ERR 13 // error LED
#define SW_A1 12 // shutter closed switch (NC)
#define SW_A2 11 // shutter open switch (NO)
#define SW_B1 10 // flap closed switch (NC)
#define SW_B2 3 // flap open switch (NO)
#define SW_INTER 2 // shutter interference detection switch (NC)
#define BUTTONS A4 // analog input for reading the buttons
#define VBAT_PIN A5 // battery voltage reading
#define BUTTON_REPS 80 // Number of ADC readings required to detect a pressed button
// Timeouts in ms
#define COMMAND_TIMEOUT 60000 // Max. time from last command
#define SHUTTER_TIMEOUT 75000 // Max. time the shutter takes to open/close
#define FLAP_TIMEOUT 15000 // Max. time the flap takes to open/close
enum {
BTN_NONE,
BTN_A_OPEN,
BTN_A_CLOSE,
BTN_B_OPEN,
BTN_B_CLOSE,
};
// Detect mechanical interfence between the two shutters
bool checkFlapInterference(State st)
{
return (st == ST_OPENING) && digitalRead(SW_INTER);
}
// Detect mechanical interfence between the two shutters
bool checkShutterInterference(State st)
{
return (st == ST_CLOSING) && digitalRead(SW_INTER) && !digitalRead(SW_B1);
}
Motor motorA(0);
Motor motorB(1);
Shutter shutter(&motorA, SW_A1, SW_A2, SHUTTER_TIMEOUT, checkShutterInterference);
Shutter flap(&motorB, SW_B1, SW_B2, FLAP_TIMEOUT, checkFlapInterference);
SerialCommand sCmd;
unsigned long lastCmdTime = 0;
// Detect a pressed button by reading an analog input.
// Every button puts a different voltage at the input.
int readButton()
{
int buttonLimits[] = {92, 303, 518, 820};
int val = analogRead(BUTTONS);
for (int i = 0; i < 4; i++) {
if (val < buttonLimits[i]) {
return i + 1;
}
}
return 0;
}
// Return dome status by combining shutter and flap statuses
State domeStatus()
{
State sst = shutter.getState();
State fst = flap.getState();
if (sst == ST_ERROR || fst == ST_ERROR)
return ST_ERROR;
else if (sst == ST_OPENING || fst == ST_OPENING)
return ST_OPENING;
else if (sst == ST_CLOSING || fst == ST_CLOSING)
return ST_CLOSING;
else if (sst == ST_OPEN || fst == ST_OPEN)
return ST_OPEN;
else if (sst == ST_CLOSED && fst == ST_CLOSED)
return ST_CLOSED;
return ST_ABORTED;
}
void cmdOpenShutter() {
lastCmdTime = millis();
shutter.open();
}
void cmdOpenBoth()
{
lastCmdTime = millis();
shutter.open();
flap.open();
}
void cmdClose()
{
lastCmdTime = millis();
shutter.close();
flap.close();
}
void cmdAbort()
{
lastCmdTime = millis();
shutter.abort();
flap.abort();
}
void cmdExit()
{
lastCmdTime = 0;
shutter.close();
flap.close();
}
void cmdStatus()
{
lastCmdTime = millis();
State st = domeStatus();
Serial.write('0' + st);
}
void cmdGetVBat()
{
lastCmdTime = millis();
int val = analogRead(VBAT_PIN);
char buffer[8];
sprintf(buffer, "v%04d", val);
Serial.write(buffer);
}
void setup()
{
wdt_disable();
wdt_enable(WDTO_1S);
pinMode(LED_ERR, OUTPUT);
// Map serial commands to functions
sCmd.addCommand("open", cmdOpenBoth);
sCmd.addCommand("open1", cmdOpenShutter);
sCmd.addCommand("close", cmdClose);
sCmd.addCommand("abort", cmdAbort);
sCmd.addCommand("exit", cmdExit);
sCmd.addCommand("stat", cmdStatus);
sCmd.addCommand("vbat", cmdGetVBat);
Serial.begin(9600);
digitalWrite(LED_ERR, HIGH);
delay(200);
digitalWrite(LED_ERR, LOW);
}
void loop()
{
int btn = readButton();
static int btn_prev = 0;
static int btn_count = 0;
if (btn && (btn == btn_prev))
btn_count++;
else
btn_count = 0;
btn_prev = btn;
if (btn_count == BUTTON_REPS) {
switch(btn) {
case BTN_A_OPEN:
shutter.open();
break;
case BTN_A_CLOSE:
shutter.close();
break;
case BTN_B_OPEN:
flap.open();
break;
case BTN_B_CLOSE:
flap.close();
break;
}
}
// Close the dome if time from last command > COMMAND_TIMEOUT
if ((lastCmdTime > 0) && ((millis() - lastCmdTime) > COMMAND_TIMEOUT)) {
if (domeStatus() != ST_CLOSED) {
lastCmdTime = 0;
shutter.close();
flap.close();
}
}
int err = (shutter.getState() == ST_ERROR) || (flap.getState() == ST_ERROR);
digitalWrite(LED_ERR, err);
shutter.update();
flap.update();
sCmd.readSerial();
wdt_reset();
}