-
Notifications
You must be signed in to change notification settings - Fork 27
/
Copy pathtimer.cpp
executable file
·421 lines (356 loc) · 9.77 KB
/
timer.cpp
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
411
412
413
414
415
416
417
418
#include <stdlib.h>
#include <stdio.h>
#include <stdint.h>
#include "common.h"
#include "timer.h"
long spindle_pwm = 0;
extern int lastS;
bool RPM_PID_MODE = false;
#ifdef RPM_COUNTER
#include "pid.h"
double rSetpoint, rInput, rOutput;
//Specify the links and initial tuning parameters
PID RPM_PID(&rInput, &rOutput, &rSetpoint, 8, 2, 12, DIRECT); //2, 5, 1, DIRECT);
uint32_t rev = 0;
uint32_t lastMillis = 0;
uint32_t RPM = 0;
int avgpw = 0;
int avgcnt = 0;
void THEISR isr_RPM() {
rev++;
}
uint32_t get_RPM() {
uint32_t milli = millis();
uint32_t delta = milli - lastMillis;
if (delta > 100) {
lastMillis = milli;
RPM = (rev * 60 * 1000 / delta);
rev = 0;
if (RPM_PID_MODE) {
rSetpoint = lastS * 100;
rInput = RPM;
RPM_PID.Compute();
if (lastS == 0)rOutput = 0;
avgpw = (avgpw + rOutput * 0.01);
avgcnt++;
#ifdef AC_SPINDLE
spindle_pwm = 10000 - pow(rOutput * 0.0001, 2) * 10000;
#else
spindle_pwm = rOutput;
#endif
}
}
return RPM;
}
void setup_RPM() {
attachInterrupt(digitalPinToInterrupt (RPM_COUNTER), isr_RPM, RISING);
lastMillis = millis();
RPM_PID.SetMode(AUTOMATIC);
RPM_PID.SetOutputLimits(0, 10000);
}
#endif
uint32_t next_l = 0;
bool spindle_state = LOW;
int spindle_pct;
//PWM Freq is 1000000/20000 = 50Hz , 20mms pulse
// for servo, the LSCALE at least 10%
#ifdef PCA9685
#ifndef spindle_servo_pin
#define spindle_servo_pin 2
#endif
// dont use classic PWM
#undef spindle_pin
#include "Wire.h"
#include "Adafruit_PWMServoDriver.h"
Adafruit_PWMServoDriver pwm = Adafruit_PWMServoDriver(0x40);
#define MIN_PULSE_WIDTH 600
#define MAX_PULSE_WIDTH 2600
#define FREQUENCY 50
#define EQ_S (FREQUENCY*4096.0/1000000)
#define EQ_A (EQ_S*MIN_PULSE_WIDTH)
#define EQ_B (EQ_S*(MAX_PULSE_WIDTH-MIN_PULSE_WIDTH)/180.0)
void setupPwm()
{
Wire.begin(D2, D1);
Wire.setClock(700000);
pwm.begin();
pwm.setPWMFreq(FREQUENCY);
pwm.setPWM(8, 0, MIN_PULSE_WIDTH);
}
int pulseWidth(int angle)
{
//int pulse_wide, analog_value;
//pulse_wide = map(angle, 0, 180, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
//analog_value = int(float(pulse_wide) / 1000000 * FREQUENCY * 4096);
return EQ_A + EQ_B * angle;
}
long lzc = 0;
void setXYZservo(float x, float y, float z) {
//long m=millis();
//if (m-lzc>20){
// lzc=m;
//pwm.setPWM(0, 0,pulseWidth(x)); // set 180 = 40mm then
//pwm.setPWM(1, 0,pulseWidth(y)); // set 180 = 40mm then
//pwm.setPWM(2, 0,pulseWidth((25+z)*4.5)); // set 180 = 40mm then
//}
}
#else
#ifdef ZERO_CROSS_PIN
void THEISR zero_cross() {
in_pwm_loop = false;
next_l = micros();
spindle_state = LOW;
xdigitalWrite(spindle_pin, LOW);
}
#endif
void setupPwm() {
#ifdef ZERO_CROSS_PIN
attachInterrupt(ZERO_CROSS_PIN, zero_cross, RAISING);
#endif
}
int pulseWidth(int angle) {
return 0;
}
void setXYZservo(float x, float y, float z) {}
// cannot use servo
#undef servo_pin
#endif
bool in_pwm_loop = false;
void set_pwm(int v) { // 0-255
if (v > 255)v = 255;
if (v < 0)v = 0;
#ifdef PLASMA_MODE
xdigitalWrite(spindle_pin,v>10);
#else
next_l = micros();
{
spindle_pct = v * 0.39; // 0 - 100
//if (! RPM_PID_MODE)
lastS = v;
extern float Lscale;
float vf;
if (int(100 * Lscale) == 0) {
vf = v > 5 ? 0 : 255;
} else {
vf = fabs(v * Lscale);
}
spindle_pwm = fmin(20000, vf * 39.216 * 2);
if (Lscale >= 0)spindle_pwm = 20000 - spindle_pwm; // flip if inverse
#ifdef spindle_pin
xdigitalWrite(spindle_pin, LOW);
#endif
#ifdef PCA9685
pwm.setPWM(spindle_servo_pin, 0, pulseWidth(0.009 * spindle_pwm)); // set 0 - 4095
return;
#endif
}
if (in_pwm_loop)return;
#ifdef spindle_pin
pinMode(spindle_pin, OUTPUT);
//xdigitalWrite(spindle_pin, HIGH);
#endif
#endif
}
void pause_pwm(bool v) {
in_pwm_loop = v;
}
void THEISR pwm_loop() {
#ifndef PLASMA_MODE
#ifdef RPM_COUNTER
get_RPM();
#endif
#ifdef spindle_pin
if (in_pwm_loop)return;
in_pwm_loop = true;
uint32_t pwmc = micros(); // next_l contain last time target for 50Hz
if ((pwmc - next_l > spindle_pwm) && (spindle_pwm < 20000)) { // if current time - next time > delta time pwm, then turn it on
if (!spindle_state) {
spindle_state = HIGH;
xdigitalWrite(spindle_pin, HIGH);
}
}
// if use zero_cross then in_pwm_loop will be true until a trigger happened
// basically replace all below using interrupt trigger
#ifndef ZERO_CROSS_PIN
if (pwmc - next_l > 19999) { // 50hz on wemos then turn off
next_l = pwmc;
spindle_state = LOW;
xdigitalWrite(spindle_pin, LOW);
}
in_pwm_loop = false;
#endif
#endif
#endif
}
void servo_set(int angle) {
#ifdef servo_pin
pwm.setPWM(servo_pin, 0, spindle_pwm * 0.205); // set 0 - 4095
return;
#endif
}
void servo_loop() {
pwm_loop();
}
int somedelay(int32_t n)
{
float f = 0;
int m = 10;
while (m--) {
int nn = n;
while (nn--) {
f += n;
asm("");
}
}
return f + n;
}
//#define somedelay(n) delayMicroseconds(n);
int dogfeed = 0;
#include<Arduino.h>
#define dogfeedevery 2200 // loop
// ESP8266 specific code here
int feedthedog()
{
if (dogfeed++ > dogfeedevery) {
dogfeed = 0;
#if defined(ESP8266)
// ESP8266 specific code here
ESP.wdtFeed();
#elif defined(ESP32)
// esp_task_wdt_reset();
#else
#endif
//zprintf(PSTR("Feed the dog\n"));
return 1;
}
return 0;
}
// ======================== TIMER for motionloop =============================
#define timerPause()
#define timerResume()
int busy1 = 0;
volatile uint32_t ndelay = 0;
uint32_t next_step_time;
inline int THEISR timercode();
// ------------------------------------- ESP8266 ----------------------------------------------------------
#ifdef ESP8266
#define USETIMEROK
#define MINDELAY 100
#define usetmr1
void THEISR tm()
{
noInterrupts();
int d = timercode();
#ifdef usetmr1
timer1_write(d < 6 ? 6 : d);
#else
timer0_write(ESP.getCycleCount() + 16 * (d < 6 ? 6 : d));
#endif
interrupts();
}
void timer_init()
{
//Initialize Ticker every 0.5s
noInterrupts();
#ifdef usetmr1
timer1_isr_init();
timer1_attachInterrupt(tm);
timer1_enable(TIM_DIV16, TIM_EDGE, TIM_SINGLE);
timer1_write(1000); //200 us
#else
timer0_isr_init();
timer0_attachInterrupt(tm);
timer0_write(ESP.getCycleCount() + 16 * 1000); //120000 us
#endif
#ifdef RPM_COUNTER
setup_RPM();
#endif
setupPwm();
set_pwm(0);
interrupts();
}
#endif // esp8266
#ifdef ESP32
#define USETIMEROK
typedef struct {
union {
struct {
uint32_t reserved0: 10;
uint32_t alarm_en: 1; /*When set alarm is enabled*/
uint32_t level_int_en: 1; /*When set level type interrupt will be generated during alarm*/
uint32_t edge_int_en: 1; /*When set edge type interrupt will be generated during alarm*/
uint32_t divider: 16; /*Timer clock (T0/1_clk) pre-scale value.*/
uint32_t autoreload: 1; /*When set timer 0/1 auto-reload at alarming is enabled*/
uint32_t increase: 1; /*When set timer 0/1 time-base counter increment. When cleared timer 0 time-base counter decrement.*/
uint32_t enable: 1; /*When set timer 0/1 time-base counter is enabled*/
};
uint32_t val;
} config;
uint32_t cnt_low; /*Register to store timer 0/1 time-base counter current value lower 32 bits.*/
uint32_t cnt_high; /*Register to store timer 0 time-base counter current value higher 32 bits.*/
uint32_t update; /*Write any value will trigger a timer 0 time-base counter value update (timer 0 current value will be stored in registers above)*/
uint32_t alarm_low; /*Timer 0 time-base counter value lower 32 bits that will trigger the alarm*/
uint32_t alarm_high; /*Timer 0 time-base counter value higher 32 bits that will trigger the alarm*/
uint32_t load_low; /*Lower 32 bits of the value that will load into timer 0 time-base counter*/
uint32_t load_high; /*higher 32 bits of the value that will load into timer 0 time-base counter*/
uint32_t reload; /*Write any value will trigger timer 0 time-base counter reload*/
} xhw_timer_reg_t;
typedef struct xhw_timer_s {
xhw_timer_reg_t * dev;
uint8_t num;
uint8_t group;
uint8_t timer;
portMUX_TYPE lock;
} xhw_timer_t;
hw_timer_t * timer = NULL;
portMUX_TYPE timerMux = portMUX_INITIALIZER_UNLOCKED;
void THEISR xtimerAlarmWrite(xhw_timer_s *timer, uint64_t alarm_value) {
timer->dev->alarm_high = (uint32_t) (alarm_value >> 32);
timer->dev->alarm_low = (uint32_t) alarm_value;
timer->dev->config.autoreload = true;
timer->dev->config.alarm_en = 1;
}
void THEISR tm() {
portENTER_CRITICAL_ISR(&timerMux);
int d = timercode();
xtimerAlarmWrite((xhw_timer_s*)timer, d < 6 ? 6 : d);
portEXIT_CRITICAL_ISR(&timerMux);
}
void timer_init()
{
timer = timerBegin(0, 80, true);
timerAttachInterrupt(timer, &tm, true);
xtimerAlarmWrite((xhw_timer_s*)timer, 12000);
//zprintf(PSTR("Time init\n"));
}
/*
#undef timerPause()
#undef timerResume()
int tmrstack=0;
void THEISR timerPause(){
tmrstack++;
if (tmrstack==1)((xhw_timer_s*) timer)->dev->config.alarm_en = 0;
}
void THEISR timerResume(){
tmrstack--;
if (tmrstack==0)((xhw_timer_s*) timer)->dev->config.alarm_en = 1;
}
*/
#endif //esp32
// ======= the same code for all cpu ======
inline int THEISR timercode() {
if (ndelay < 30000) {
ndelay = MINDELAY;
coreloopm();
} else {
ndelay -= 30000;
}
//pwm_loop();
return ndelay >= 30000 ? 30000 : ndelay;
}
// ==============================================
// Laser constant burn timer
void THEISR timer_set(int32_t delay)
{
ndelay = delay;
}