/
ports.c
410 lines (375 loc) · 10.8 KB
/
ports.c
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
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
/*
* ports.c Manage ports control
* This library use the ATMega2560 ports map
*/
#include "grbl.h"
// Blocked pins
const uint8_t workPin[38] = {
STEP_X, STEP_Y, STEP_Z, STEP_A,
DIR_X, DIR_Y, DIR_Z, DIR_A,
ENABLE,
RELAY_1, RELAY_2,
MAX_X, MAX_Y, MAX_Z,
MIN_X, MIN_Y, MIN_Z,
PROBE, PAUSE, STOP, PLAY,
JOP_VEL_1, JOP_VEL_2, JOP_VEL_3, JOP_XA, JOP_XB, JOP_YA, JOP_YB, JOP_ZA, JOP_ZB,
ANALOG_1, ANALOG_2, ANALOG_3, ANALOG_4,
MISO, MOSI, SCK, CS};
const workPinSize = 38;
/**
* Check if pin is in use from maping
*
* @param pin
* @return true // Pin can be used
* @return false // Pin blocked
*/
bool pinBlocked(uint8_t pin)
{
for (uint8_t j = 0; j < workPinSize; j++)
{
if (workPin[j] == pin)
return true;
}
return false;
}
/**
* Synchronic waint for pin implementation
*
* @param line
* @return uint8_t // Result of command process
* // 1 - Format problem
* // 2 - Pin blocked
* // 3 - Ok
*/
uint8_t waintForPinSync(char *line)
{
uint8_t pinVal; // Pin value (1-97)
uint8_t stateVal; // Pin state (0-1)
// Get pin value
if (line[4] == 'P')
{
char v[2];
v[0] = v[1] = 0;
uint8_t vi = 0;
for (uint8_t i = 5; i <= 6; i++)
{
if (line[i] == 'S' || line[i] == '\r' || line[i] == '\n')
break;
v[vi] = line[i];
vi++;
}
//Convert pin value
pinVal = atoi(v);
// Check if pin is blocked
if (pinBlocked(pinVal)) return 2;
// Get state value
if (line[5 + vi] == 'S')
{
char s[2];
s[0] = line[6 + vi];
stateVal = atoi(s);
}
else
{
// Bad format
return 1;
}
}
else
{
// Bad format
return 1;
}
protocol_buffer_synchronize(); // Sync and finish all remaining buffered motions before moving on.
protocol_execute_realtime(); // Execute suspend.
while (digitalRead(pinVal) != stateVal)
{
}
protocol_exec_rt_system(); // Executes run-time commands
return 3; // OK
}
/**
* Waint for pin implementation
*
* @param line
* @return uint8_t // Result of command process
* // 1 - Format problem
* // 2 - Pin blocked
* // 3 - Ok
*/
uint8_t waintForPinAsync(char *line)
{
uint8_t pinVal; // Pin value (1-97)
uint8_t stateVal; // Pin state (0-1)
// Get pin value
if (line[4] == 'P')
{
char v[2];
v[0] = v[1] = 0;
uint8_t vi = 0;
for (uint8_t i = 5; i <= 6; i++)
{
if (line[i] == 'S' || line[i] == '\r' || line[i] == '\n')
break;
v[vi] = line[i];
vi++;
}
//Convert pin value
pinVal = atoi(v);
// Check if pin is blocked
if (pinBlocked(pinVal)) return 2;
// Get state value
if (line[5 + vi] == 'S')
{
char s[2];
s[0] = line[6 + vi];
stateVal = atoi(s);
}
else
{
// Bad format
return 1;
}
}
else
{
// Bad format
return 1;
}
protocol_execute_realtime(); // Execute suspend.
while (digitalRead(pinVal) != stateVal)
{
}
protocol_exec_rt_system(); // Executes run-time commands
return 3; // OK
}
/**
* Precess the ports command lines
* All params must be in the rigth order and use correct letters
*
* @param line // Command line
* @return uint8_t // Result of command process
* // 1 - Format problem
* // 2 - Pin blocked
* // 3 - Ok
*/
uint8_t ports_manage(char *line)
{
uint8_t pinVal; // Pin value (1-97)
uint8_t stateVal; // Pin state (0-1)
uint8_t modeVal; // Pin mode (0-2)
// Get pinvalue
if (line[3] == 'P')
{
char v[2];
v[0] = v[1] = 0;
uint8_t vi = 0;
for (uint8_t i = 4; i <= 5; i++)
{
if (line[i] == 'M' || line[i] == 'R' || line[i] == 'S' || line[i] == '\r' || line[i] == '\n')
break;
v[vi] = line[i];
vi++;
}
//Convert pin value
pinVal = atoi(v);
// Check if pin is blocked
if (pinBlocked(pinVal)) return 2;
// Get pin mode
if (line[4 + vi] == 'M')
{
char s[2];
s[0] = line[5 + vi];
modeVal = atoi(s);
pinMode((uint8_t)pinVal, (uint8_t)modeVal);
}
// Get pin state
if (line[4 + vi] == 'S')
{
char s[2];
s[0] = line[5 + vi];
// Convert value
stateVal = atoi(s);
// Write value to pin
digitalWrite(pinVal, stateVal);
}
// Check for read command
if (line[4 + vi] == 'R')
{
// Return pin value
if (digitalRead(pinVal) == 0)
{
printPgmString(PSTR("LOW"));
}
else
{
printPgmString(PSTR("HIGH"));
}
printPgmString(PSTR("\r\n"));
}
}
else
{
// Bad format
return 1;
}
// OK
return 3;
}
/**
* Configure alarm pin interruption
*
*/
void alarmsInit()
{
alarmTriggered = false;
/*
+----------+------+--------------------+----------------------+-----------+
| PIN name | Port | Digital pin number | Alarm | INTR |
+----------+------+--------------------+----------------------+-----------+
| A13 | PK5 | 84 | Alarm OUT Servo X2 | PCINT21 |
+----------+------+--------------------+----------------------+-----------+
| A14 | PK6 | 83 | Alarm OUT Servo Y | PCINT22 |
+----------+------+--------------------+----------------------+-----------+
| D11 | PB5 | 24 | Power Source fault | PCINT5 |
+----------+------+--------------------+----------------------+-----------+
| D12 | PB6 | 25 | Tourch Signal | PCINT6 |
+----------+------+--------------------+----------------------+-----------+
| D13 | PB7 | 26 | Alarm OUT Servo X1 | PCINT7 |
+----------+------+--------------------+----------------------+-----------+
*/
// Port B Configuration
DDRB &= ~((1<<POWER_SOURCE_FAULT_BIT)|(1<<ALARM_TOURCH_SIGNAL_BIT)|(1<<ALARM_OUT_SERVO_X1_BIT)); // Configure as input pins
PORTB |= ((1<<POWER_SOURCE_FAULT_BIT)|(1<<ALARM_TOURCH_SIGNAL_BIT)|(1<<ALARM_OUT_SERVO_X1_BIT)); // Enable internal pull-up resistors. Normal high operation.
PCMSK0 |= ((1<<POWER_SOURCE_FAULT_BIT)|(1<<ALARM_TOURCH_SIGNAL_BIT)|(1<<ALARM_OUT_SERVO_X1_BIT)); // Enable specific pins of the Pin Change Interrupt
PCICR |= (1 << PCIE0); // Enable Pin Change Interrupt
// Port K Configuration
DDRK &= ~((1<<ALARM_OUT_SERVO_X2_BIT)|(1<<ALARM_OUT_SERVO_Y_BIT)); // Configure as input pins
PORTK |= ((1<<ALARM_OUT_SERVO_X2_BIT)|(1<<ALARM_OUT_SERVO_Y_BIT)); // Enable internal pull-up resistors. Normal high operation.
PCMSK2 |= ((1<<ALARM_OUT_SERVO_X2_BIT)|(1<<ALARM_OUT_SERVO_Y_BIT)); // Enable specific pins of the Pin Change Interrupt
PCICR |= (1 << PCIE2); // Enable Pin Change Interrupt
}
/**
* Disable all alarms
*
*/
void alarmsDisable(){
// Disable Specific Pin Change Interrupt Port B
PCMSK0 &= ~((1<<POWER_SOURCE_FAULT_BIT)|(1<<ALARM_TOURCH_SIGNAL_BIT)|(1<<ALARM_OUT_SERVO_X1_BIT)); // Disable specific pins of the Pin Change Interrupt
// Disable Specific Pin Change Interrupt Port K
PCMSK2 &= ~((1<<ALARM_OUT_SERVO_X2_BIT)|(1<<ALARM_OUT_SERVO_Y_BIT)); // Enable specific pins of the Pin Change Interrupt
}
/**
* Enable alarm by pin and port
*
* @param port
* @param bit
*/
void alarmDisable(char port,uint8_t bit){
if(port=='B'){
PCMSK0 &= ~(1<<bit);
}else{
if(port=='K'){
PCMSK2 &= ~(1<<bit);
}
}
}
/**
* Disable alarm by pin and port
*
* @param port
* @param bit
*/
void alarmEnable(char port,uint8_t bit){
if(port=='B'){
PCMSK0 |= (1<<bit);
}else{
if(port=='K'){
PCMSK2 |= (1<<bit);
}
}
alarmTriggered = false;
}
/**
* Restore last alarm triggered and movement
*
*/
void movementRestore(){
system_set_exec_state_flag(EXEC_CYCLE_START);
}
// Pin change interrupt
ISR(PCINT0_vect)
{
if(alarmTriggered) return;
// Read port B, only 5,6 and 7 pins and check interruption state mask
uint8_t pin = (PINB & ((1<<POWER_SOURCE_FAULT_BIT)|(1<<ALARM_TOURCH_SIGNAL_BIT)|(1<<ALARM_OUT_SERVO_X1_BIT)));
// Check for correct state of pins
pin ^= PORTB_PCINTERRUPT_STATE_MASK;
// Report feedback in each case and feed hold
if(((pin & (1<<POWER_SOURCE_FAULT_BIT)))){
alarmTriggered = true;
activeAlarmPort = 'B';
activeAlarmBit = POWER_SOURCE_FAULT_BIT;
alarmDisable(activeAlarmPort,activeAlarmBit);
system_set_exec_state_flag(EXEC_FEED_HOLD);
report_feedback_message(MESSAGE_POWER_SOURCE_FAULT);
}else if((pin & (1<<ALARM_TOURCH_SIGNAL_BIT))){
alarmTriggered = true;
activeAlarmPort = 'B';
activeAlarmBit = ALARM_TOURCH_SIGNAL_BIT;
alarmDisable(activeAlarmPort,activeAlarmBit);
system_set_exec_state_flag(EXEC_FEED_HOLD);
report_feedback_message(MESSAGE_ALARM_TOURCH_SIGNAL);
}else if((pin & (1<<ALARM_OUT_SERVO_X1_BIT))){
alarmTriggered = true;
activeAlarmPort = 'B';
activeAlarmBit = ALARM_OUT_SERVO_X1_BIT;
alarmDisable(activeAlarmPort,activeAlarmBit);
system_set_exec_state_flag(EXEC_FEED_HOLD);
report_feedback_message(MESSAGE_ALARM_OUT_SERVO_X1);
}
}
/**
* Disable Stepper, assume disable 0 logic
*
* */
void stepperDisable(char *line){
if(line[3]){
if(line[3]=='X'){
// X Disable - Pin D38
STEPPER_DISABLE_PORT(0) &= ~(1 << STEPPER_DISABLE_BIT(0));
}else if(line[3]=='Y'){
// Y Disable - Pin A2
STEPPER_DISABLE_PORT(1) &= ~(1 << STEPPER_DISABLE_BIT(1));
}else if(line[3]=='Z'){
// Z Disable - Pin A8
STEPPER_DISABLE_PORT(2) &= ~(1 << STEPPER_DISABLE_BIT(2));
}
}else{
STEPPER_DISABLE_PORT(0) &= ~(1 << STEPPER_DISABLE_BIT(0));
STEPPER_DISABLE_PORT(1) &= ~(1 << STEPPER_DISABLE_BIT(1));
STEPPER_DISABLE_PORT(2) &= ~(1 << STEPPER_DISABLE_BIT(2));
}
}
/**
* Enable Stepper, assume enable 1 logic
*
* */
void stepperEnable(char *line){
if(line[3]){
if(line[3]=='X'){
// X Enable - Pin D38
STEPPER_DISABLE_PORT(0) |= (1 << STEPPER_DISABLE_BIT(0));
}else if(line[3]=='Y'){
// Y Enable - Pin A2
STEPPER_DISABLE_PORT(1) |= (1 << STEPPER_DISABLE_BIT(1));
}else if(line[3]=='Z'){
// Z Enable - Pin A8
STEPPER_DISABLE_PORT(2) |= (1 << STEPPER_DISABLE_BIT(2));
}
}else{
STEPPER_DISABLE_PORT(0) |= (1 << STEPPER_DISABLE_BIT(0));
STEPPER_DISABLE_PORT(1) |= (1 << STEPPER_DISABLE_BIT(1));
STEPPER_DISABLE_PORT(2) |= (1 << STEPPER_DISABLE_BIT(2));
}
}