-
Notifications
You must be signed in to change notification settings - Fork 42
/
driver.c
2049 lines (1712 loc) · 58.7 KB
/
driver.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
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*
driver.c - An embedded CNC Controller with rs274/ngc (g-code) support
Driver code for ESP32
Part of grblHAL
Copyright (c) 2018-2021 Terje Io
Some parts
Copyright (c) 2011-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
Grbl is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <stdlib.h>
#include <stdbool.h>
#include <string.h>
#include "driver.h"
#include "esp32-hal-uart.h"
#include "nvs.h"
#include "esp_log.h"
#include "sdkconfig.h"
#include "esp_ota_ops.h"
//#include "grbl_esp32_if/grbl_esp32_if.h"
#include "grbl/limits.h"
#include "grbl/protocol.h"
#include "grbl/state_machine.h"
#include "grbl/motor_pins.h"
#ifdef USE_I2S_OUT
#include "i2s_out.h"
#endif
#if WIFI_ENABLE
#include "wifi.h"
#endif
#if WEBUI_ENABLE
#include "webui/response.h"
#endif
#if TELNET_ENABLE
#include "networking/TCPStream.h"
#endif
#if WEBSOCKET_ENABLE
#include "networking/WsStream.h"
#endif
#if BLUETOOTH_ENABLE
#include "bluetooth.h"
#endif
#if SDCARD_ENABLE
#include "sdcard/sdcard.h"
#include "esp_vfs_fat.h"
#endif
#if KEYPAD_ENABLE
#include "keypad/keypad.h"
#endif
#if IOEXPAND_ENABLE
#include "ioexpand.h"
#endif
#if EEPROM_ENABLE
#include "eeprom/eeprom.h"
#endif
#if I2C_ENABLE
#include "i2c.h"
#endif
#if VFD_SPINDLE != 1
static uint32_t pwm_max_value;
static bool pwmEnabled = false;
static spindle_pwm_t spindle_pwm;
#else
#undef SPINDLE_RPM_CONTROLLED
#endif
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/timers.h"
// prescale step counter to 20Mhz
#define STEPPER_DRIVER_PRESCALER 4
#if PWM_RAMPED
#define SPINDLE_RAMP_STEP_INCR 20 // timer compare register change per ramp step
#define SPINDLE_RAMP_STEP_TIME 2 // ms
typedef struct {
volatile uint32_t ms_cfg;
volatile uint32_t ms_count;
uint32_t pwm_current;
uint32_t pwm_target;
uint32_t pwm_step;
} pwm_ramp_t;
static pwm_ramp_t pwm_ramp;
#endif
const io_stream_t *serial_stream;
#if MPG_MODE_ENABLE
static io_stream_t prev_stream = {0}, *mpg_stream;
#endif
static periph_signal_t *periph_pins = NULL;
static input_signal_t inputpin[] = {
#ifdef RESET_PIN
{ .id = Input_Reset, .pin = RESET_PIN, .group = PinGroup_Control },
#endif
#ifdef FEED_HOLD_PIN
{ .id = Input_FeedHold, .pin = FEED_HOLD_PIN, .group = PinGroup_Control },
#endif
#ifdef CYCLE_START_PIN
{ .id = Input_CycleStart, .pin = CYCLE_START_PIN, .group = PinGroup_Control },
#endif
#ifdef SAFETY_DOOR_PIN
{ .id = Input_SafetyDoor, .pin = SAFETY_DOOR_PIN, .group = PinGroup_Control },
#endif
#ifdef PROBE_PIN
{ .id = Input_Probe, .pin = PROBE_PIN, .group = PinGroup_Probe },
#endif
{ .id = Input_LimitX, .pin = X_LIMIT_PIN, .group = PinGroup_Limit },
#ifdef X2_LIMIT_PIN
{ .id = Input_LimitX_2, .pin = X2_LIMIT_PIN, .group = PinGroup_Limit },
#endif
{ .id = Input_LimitY, .pin = Y_LIMIT_PIN, .group = PinGroup_Limit },
#ifdef Y2_LIMIT_PIN
{ .id = Input_LimitY_2, .pin = Y2_LIMIT_PIN, .group = PinGroup_Limit },
#endif
{ .id = Input_LimitZ, .pin = Z_LIMIT_PIN, .group = PinGroup_Limit },
#ifdef Z2_LIMIT_PIN
{ .id = Input_LimitZ_2, .pin = Z2_LIMIT_PIN, .group = PinGroup_Limit },
#endif
#ifdef A_LIMIT_PIN
{ .id = Input_LimitA, .pin = A_LIMIT_PIN, .group = PinGroup_Limit },
#endif
#ifdef B_LIMIT_PIN
{ .id = Input_LimitB, .pin = B_LIMIT_PIN, .group = PinGroup_Limit },
#endif
#ifdef C_LIMIT_PIN
{ .id = Input_LimitC, .pin = C_LIMIT_PIN, .group = PinGroup_Limit },
#endif
#if MPG_MODE_ENABLE
{ .id = Input_ModeSelect, .pin = MPG_ENABLE_PIN, .group = PinGroup_MPG },
#endif
#ifdef I2C_STROBE_PIN
{ .id = Input_KeypadStrobe, .pin = I2C_STROBE_PIN, .group = PinGroup_Keypad }
#endif
};
static output_signal_t outputpin[] =
{
#ifndef USE_I2S_OUT
{ .id = Output_StepX, .pin = X_STEP_PIN, .group = PinGroup_StepperStep, .mode = Pin_RMT },
{ .id = Output_StepY, .pin = Y_STEP_PIN, .group = PinGroup_StepperStep, .mode = Pin_RMT },
{ .id = Output_StepZ, .pin = Z_STEP_PIN, .group = PinGroup_StepperStep, .mode = Pin_RMT },
#endif
#if defined(STEPPERS_DISABLE_PIN) && STEPPERS_DISABLE_PIN != IOEXPAND
{ .id = Output_StepperEnable, .pin = STEPPERS_DISABLE_PIN, .group = PinGroup_StepperEnable },
#endif
#if defined(SPINDLE_ENABLE_PIN) && SPINDLE_ENABLE_PIN != IOEXPAND
{ .id = Output_SpindleOn, .pin = SPINDLE_ENABLE_PIN, .group = PinGroup_SpindleControl },
#endif
#if defined(SPINDLE_DIRECTION_PIN) && SPINDLE_DIRECTION_PIN != IOEXPAND
{ .id = Output_SpindleDir, .pin = SPINDLE_DIRECTION_PIN, .group = PinGroup_SpindleControl },
#endif
#if defined(COOLANT_FLOOD_PIN) && COOLANT_FLOOD_PIN != IOEXPAND
{ .id = Output_CoolantFlood, .pin = COOLANT_FLOOD_PIN, .group = PinGroup_Coolant },
#endif
#if defined(COOLANT_MIST_PIN) && COOLANT_MIST_PIN != IOEXPAND
{ .id = Output_CoolantMist, .pin = COOLANT_MIST_PIN, .group = PinGroup_Coolant },
#endif
{ .id = Output_DirX, .pin = X_DIRECTION_PIN, .group = PinGroup_StepperDir },
{ .id = Output_DirY, .pin = Y_DIRECTION_PIN, .group = PinGroup_StepperDir },
{ .id = Output_DirZ, .pin = Z_DIRECTION_PIN, .group = PinGroup_StepperDir },
#ifdef A_AXIS
{ .id = Output_DirA, .pin = A_DIRECTION_PIN, .group = PinGroup_StepperDir },
#endif
#ifdef B_AXIS
{ .id = Output_DirB, .pin = B_DIRECTION_PIN, .group = PinGroup_StepperDir },
#endif
#ifdef C_AXIS
{ .id = Output_DirC, .pin = C_DIRECTION_PIN, .group = PinGroup_StepperDir },
#endif
#ifdef X2_DIRECTION_PIN
{ .id = Output_DirX_2, .pin = X2_DIRECTION_PIN, .group = PinGroup_StepperDir },
#endif
#ifdef Y2_DIRECTION_PIN
{ .id = Output_DirY_2, .pin = Y2_DIRECTION_PIN, .group = PinGroup_StepperDir },
#endif
#ifdef Z2_DIRECTION_PIN
{ .id = Output_DirZ_2, .pin = Z2_DIRECTION_PIN, .group = PinGroup_StepperDir },
#endif
#ifdef MOTOR_CS_PIN
{ .id = Output_MotorChipSelect, .pin = MOTOR_CS_PIN, .group = PinGroup_MotorChipSelect },
#endif
#ifdef MOTOR_CSX_PIN
{ .id = Output_MotorChipSelectX, .pin = MOTOR_CSX_PIN, .group = PinGroup_MotorChipSelect },
#endif
#ifdef MOTOR_CSY_PIN
{ .id = Output_MotorChipSelectY, .pin = MOTOR_CSY_PIN, .group = PinGroup_MotorChipSelect },
#endif
#ifdef MOTOR_CSZ_PIN
{ .id = Output_MotorChipSelectZ, .pin = MOTOR_CSZ_PIN, .group = PinGroup_MotorChipSelect },
#endif
#ifdef MOTOR_CSM3_PIN
{ .id = Output_MotorChipSelectM3, .pin = MOTOR_CSM3_PIN, .group = PinGroup_MotorChipSelect },
#endif
#ifdef MOTOR_CSM4_PIN
{ .id = Output_MotorChipSelectM4, .pin = MOTOR_CSM4_PIN, .group = PinGroup_MotorChipSelect },
#endif
#ifdef MOTOR_CSM5_PIN
{ .id = Output_MotorChipSelectM5, .pin = MOTOR_CSM5_PIN, .group = PinGroup_MotorChipSelect },
#endif
#ifdef MODBUS_DIRECTION_PIN
{ .id = Output_Aux0, .pin = MODBUS_DIRECTION_PIN, .group = PinGroup_AuxOutput },
#endif
};
static volatile uint32_t ms_count = 1; // NOTE: initial value 1 is for "resetting" systick timer
static bool IOInitDone = false;
static portMUX_TYPE mux = portMUX_INITIALIZER_UNLOCKED;
#if PROBE_ENABLE
static probe_state_t probe = {
.connected = On
};
#endif
#ifdef SQUARING_ENABLED
static axes_signals_t motors_1 = {AXES_BITMASK}, motors_2 = {AXES_BITMASK};
#endif
#ifdef USE_I2S_OUT
uint32_t i2s_step_length = I2S_OUT_USEC_PER_PULSE, i2s_step_samples = 1;
#endif
#if IOEXPAND_ENABLE
static ioexpand_t iopins = {0};
#endif
#if I2C_STROBE_ENABLE
static driver_irq_handler_t i2c_strobe = { .type = IRQ_I2C_Strobe };
static bool irq_claim (irq_type_t irq, uint_fast8_t id, irq_callback_ptr handler)
{
bool ok;
if((ok = irq == IRQ_I2C_Strobe && i2c_strobe.callback == NULL))
i2c_strobe.callback = handler;
return ok;
}
#endif
#if VFD_SPINDLE != 1
static void spindle_set_speed (uint_fast16_t pwm_value);
static ledc_timer_config_t ledTimerConfig = {
.speed_mode = LEDC_HIGH_SPEED_MODE,
.duty_resolution = LEDC_TIMER_10_BIT,
.timer_num = LEDC_TIMER_0,
.freq_hz = 5000
};
static ledc_channel_config_t ledConfig = {
.gpio_num = SPINDLEPWMPIN,
.speed_mode = LEDC_HIGH_SPEED_MODE,
.channel = LEDC_CHANNEL_0,
.intr_type = LEDC_INTR_DISABLE,
.timer_sel = LEDC_TIMER_0,
.duty = 0, /*!< LEDC channel duty, the range of duty setting is [0, (2**duty_resolution)] */
.hpoint = 0
};
#endif
// Interrupt handler prototypes
static void gpio_isr (void *arg);
static void stepper_driver_isr (void *arg);
static TimerHandle_t xDelayTimer = NULL, debounceTimer = NULL;
void initRMT (settings_t *settings)
{
rmt_item32_t rmtItem[2];
rmt_config_t rmtConfig = {
.rmt_mode = RMT_MODE_TX,
.clk_div = 20,
.mem_block_num = 1,
.tx_config.loop_en = false,
.tx_config.carrier_en = false,
.tx_config.carrier_freq_hz = 0,
.tx_config.carrier_duty_percent = 50,
.tx_config.carrier_level = RMT_CARRIER_LEVEL_LOW,
.tx_config.idle_output_en = true
};
rmtItem[0].duration0 = (uint32_t)(settings->steppers.pulse_delay_microseconds > 0.0f ? 4.0f * settings->steppers.pulse_delay_microseconds : 1.0f);
rmtItem[0].duration1 = (uint32_t)(4.0f * settings->steppers.pulse_microseconds);
rmtItem[1].duration0 = 0;
rmtItem[1].duration1 = 0;
uint32_t channel;
for(channel = 0; channel < (N_AXIS + N_ABC_MOTORS); channel++) {
rmtConfig.channel = channel;
switch(channel) {
case X_AXIS:
rmtConfig.tx_config.idle_level = settings->steppers.step_invert.x;
rmtConfig.gpio_num = X_STEP_PIN;
break;
case Y_AXIS:
rmtConfig.tx_config.idle_level = settings->steppers.step_invert.y;
rmtConfig.gpio_num = Y_STEP_PIN;
break;
case Z_AXIS:
rmtConfig.tx_config.idle_level = settings->steppers.step_invert.z;
rmtConfig.gpio_num = Z_STEP_PIN;
break;
#ifdef A_STEP_PIN
case A_AXIS:
rmtConfig.tx_config.idle_level = settings->steppers.step_invert.a;
rmtConfig.gpio_num = A_STEP_PIN;
break;
#endif
#ifdef B_STEP_PIN
case B_AXIS:
rmtConfig.tx_config.idle_level = settings->steppers.step_invert.b;
rmtConfig.gpio_num = B_STEP_PIN;
break;
#endif
#ifdef C_STEP_PIN
case C_AXIS:
rmtConfig.tx_config.idle_level = settings->steppers.step_invert.c;
rmtConfig.gpio_num = C_STEP_PIN;
break;
#endif
#ifdef X2_STEP_PIN
case X2_MOTOR:
rmtConfig.tx_config.idle_level = settings->steppers.step_invert.x;
rmtConfig.gpio_num = X2_STEP_PIN;
break;
#endif
#ifdef Y2_STEP_PIN
case Y2_MOTOR:
rmtConfig.tx_config.idle_level = settings->steppers.step_invert.y;
rmtConfig.gpio_num = Y2_STEP_PIN;
break;
#endif
#ifdef Z2_STEP_PIN
case Z2_MOTOR:
rmtConfig.tx_config.idle_level = settings->steppers.step_invert.y;
rmtConfig.gpio_num = Z2_STEP_PIN;
break;
#endif
}
rmtItem[0].level0 = rmtConfig.tx_config.idle_level;
rmtItem[0].level1 = !rmtConfig.tx_config.idle_level;
rmt_config(&rmtConfig);
rmt_fill_tx_items(rmtConfig.channel, &rmtItem[0], 2, 0);
}
}
void vTimerCallback (TimerHandle_t xTimer)
{
void (*callback)(void) = (void (*)(void))pvTimerGetTimerID(xTimer);
if(callback)
callback();
xTimerDelete(xDelayTimer, 3);
xDelayTimer = NULL;
}
IRAM_ATTR static void driver_delay_ms (uint32_t ms, void (*callback)(void))
{
if(callback) {
BaseType_t xHigherPriorityTaskWoken = pdFALSE;
if(xDelayTimer) {
xTimerDelete(xDelayTimer, 3);
xDelayTimer = NULL;
}
xDelayTimer = xTimerCreate("msDelay", pdMS_TO_TICKS(ms), pdFALSE, callback, vTimerCallback);
xTimerStartFromISR(xDelayTimer, &xHigherPriorityTaskWoken);
if(xHigherPriorityTaskWoken)
portYIELD_FROM_ISR();
} else {
if(xDelayTimer) {
xTimerDelete(xDelayTimer, 3);
xDelayTimer = NULL;
}
vTaskDelay(pdMS_TO_TICKS(ms));
}
}
#ifdef DEBUGOUT
static void debug_out (bool enable)
{
gpio_set_level(STEPPERS_DISABLE_PIN, enable);
}
#endif
// Enable/disable steppers
static void stepperEnable (axes_signals_t enable)
{
enable.mask ^= settings.steppers.enable_invert.mask;
#if !TRINAMIC_MOTOR_ENABLE
#if IOEXPAND_ENABLE // TODO: read from expander?
iopins.stepper_enable_x = enable.x;
iopins.stepper_enable_y = enable.y;
iopins.stepper_enable_z = enable.z;
ioexpand_out(iopins);
#elif defined(STEPPERS_DISABLE_PIN)
DIGITAL_OUT(STEPPERS_DISABLE_PIN, enable.x);
#else
#ifdef X_DISABLE_PIN
DIGITAL_OUT(X_DISABLE_PIN, enable.x);
#endif
#ifdef X_DISABLE_PIN
DIGITAL_OUT(Y_DISABLE_PIN, enable.y);
#endif
#ifdef Z_DISABLE_PIN
DIGITAL_OUT(Z_DISABLE_PIN, enable.z);
#endif
#ifdef A_DISABLE_PIN
DIGITAL_OUT(A_DISABLE_PIN, enable.a);
#endif
#ifdef B_DISABLE_PIN
DIGITAL_OUT(B_DISABLE_PIN, enable.b);
#endif
#ifdef C_DISABLE_PIN
DIGITAL_OUT(C_DISABLE_PIN, enable.c);
#endif
#endif
#endif
}
#ifdef USE_I2S_OUT
IRAM_ATTR static void I2S_stepperCyclesPerTick (uint32_t cycles_per_tick)
{
i2s_out_set_pulse_period(cycles_per_tick);
}
// Sets stepper direction and pulse pins and starts a step pulse
IRAM_ATTR static void I2S_stepperPulseStart (stepper_t *stepper)
{
if(stepper->dir_change)
set_dir_outputs(stepper->dir_outbits);
if(stepper->step_outbits.value) {
i2s_set_step_outputs(stepper->step_outbits);
i2s_out_push_sample(i2s_step_samples);
i2s_set_step_outputs((axes_signals_t){0});
}
}
// Starts stepper driver ISR timer and forces a stepper driver interrupt callback
static void I2S_stepperWakeUp (void)
{
// Enable stepper drivers.
stepperEnable((axes_signals_t){AXES_BITMASK});
i2s_out_set_stepping();
}
#else
// Starts stepper driver ISR timer and forces a stepper driver interrupt callback
static void stepperWakeUp (void)
{
// Enable stepper drivers.
stepperEnable((axes_signals_t){AXES_BITMASK});
timer_set_counter_value(STEP_TIMER_GROUP, STEP_TIMER_INDEX, 0x00000000ULL);
// timer_set_alarm_value(STEP_TIMER_GROUP, STEP_TIMER_INDEX, 5000ULL);
TIMERG0.hw_timer[STEP_TIMER_INDEX].alarm_high = 0;
TIMERG0.hw_timer[STEP_TIMER_INDEX].alarm_low = 5000UL;
timer_start(STEP_TIMER_GROUP, STEP_TIMER_INDEX);
TIMERG0.hw_timer[STEP_TIMER_INDEX].config.alarm_en = TIMER_ALARM_EN;
}
// Sets up stepper driver interrupt timeout
IRAM_ATTR static void stepperCyclesPerTick (uint32_t cycles_per_tick)
{
// Limit min steps/s to about 2 (hal.f_step_timer @ 20MHz)
#ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING
TIMERG0.hw_timer[STEP_TIMER_INDEX].alarm_low = cycles_per_tick < (1UL << 18) ? cycles_per_tick : (1UL << 18) - 1UL;
#else
TIMERG0.hw_timer[STEP_TIMER_INDEX].alarm_low = cycles_per_tick < (1UL << 23) ? cycles_per_tick : (1UL << 23) - 1UL;
#endif
}
#endif // USE_I2S_OUT
#ifdef SQUARING_ENABLED
#ifdef USE_I2S_OUT
// Set stepper pulse output pins
inline __attribute__((always_inline)) IRAM_ATTR static void i2s_set_step_outputs (axes_signals_t step_outbits_1)
{
axes_signals_t step_outbits_2;
step_outbits_2.mask = (step_outbits_1.mask & motors_2.mask) ^ settings.steppers.step_invert.mask;
step_outbits_1.mask = (step_outbits_1.mask & motors_1.mask) ^ settings.steppers.step_invert.mask;
DIGITAL_OUT(X_STEP_PIN, step_outbits_1.x);
DIGITAL_OUT(Y_STEP_PIN, step_outbits_1.y);
DIGITAL_OUT(Z_STEP_PIN, step_outbits_1.z);
#ifdef X2_STEP_PIN
DIGITAL_OUT(X_STEP_PIN, step_outbits_2.x);
#endif
#ifdef Y2_STEP_PIN
DIGITAL_OUT(X_STEP_PIN, step_outbits_2.y);
#endif
#ifdef Z2_STEP_PIN
DIGITAL_OUT(X_STEP_PIN, step_outbits_2.z);
#endif
#ifdef A_AXIS
DIGITAL_OUT(A_STEP_PIN, step_outbits_1.a);
#endif
#ifdef B_AXIS
DIGITAL_OUT(B_STEP_PIN, step_outbits_1.b);
#endif
#ifdef C_AXIS
DIGITAL_OUT(C_STEP_PIN, step_outbits_1.c);
#endif
}
#else
// Set stepper pulse output pins
inline IRAM_ATTR static void set_step_outputs (axes_signals_t step_outbits_1)
{
axes_signals_t step_outbits_2;
step_outbits_2.mask = (step_outbits_1.mask & motors_2.mask) ^ settings.steppers.step_invert.mask;
// step_outbits_1.mask = (step_outbits_1.mask & motors_1.mask) ^ settings.steppers.step_invert.mask;
if(step_outbits_1.x) {
RMT.conf_ch[X_AXIS].conf1.mem_rd_rst = 1;
RMT.conf_ch[X_AXIS].conf1.tx_start = 1;
}
if(step_outbits_1.y) {
RMT.conf_ch[Y_AXIS].conf1.mem_rd_rst = 1;
RMT.conf_ch[Y_AXIS].conf1.tx_start = 1;
}
if(step_outbits_1.z) {
RMT.conf_ch[Z_AXIS].conf1.mem_rd_rst = 1;
RMT.conf_ch[Z_AXIS].conf1.tx_start = 1;
}
#ifdef X2_STEP_PIN
if(step_outbits_2.x) {
RMT.conf_ch[X2_MOTOR].conf1.mem_rd_rst = 1;
RMT.conf_ch[X2_MOTOR].conf1.tx_start = 1;
}
#endif
#ifdef Y2_STEP_PIN
if(step_outbits_2.y) {
RMT.conf_ch[Y2_MOTOR].conf1.mem_rd_rst = 1;
RMT.conf_ch[Y2_MOTOR].conf1.tx_start = 1;
}
#endif
#ifdef Z2_STEP_PIN
if(step_outbits_2.z) {
RMT.conf_ch[Z2_MOTOR].conf1.mem_rd_rst = 1;
RMT.conf_ch[Z2_MOTOR].conf1.tx_start = 1;
}
#endif
#ifdef A_STEP_PIN
if(step_outbits_1.a) {
RMT.conf_ch[A_AXIS].conf1.mem_rd_rst = 1;
RMT.conf_ch[A_AXIS].conf1.tx_start = 1;
}
#endif
#ifdef B_STEP_PIN
if(step_outbits_1.b) {
RMT.conf_ch[B_AXIS].conf1.mem_rd_rst = 1;
RMT.conf_ch[B_AXIS].conf1.tx_start = 1;
}
#endif
#ifdef C_STEP_PIN
if(step_outbits_1.c) {
RMT.conf_ch[C_AXIS].conf1.mem_rd_rst = 1;
RMT.conf_ch[C_AXIS].conf1.tx_start = 1;
}
#endif
}
#endif
// Enable/disable motors for auto squaring of ganged axes
static void StepperDisableMotors (axes_signals_t axes, squaring_mode_t mode)
{
motors_1.mask = (mode == SquaringMode_A || mode == SquaringMode_Both ? axes.mask : 0) ^ AXES_BITMASK;
motors_2.mask = (mode == SquaringMode_B || mode == SquaringMode_Both ? axes.mask : 0) ^ AXES_BITMASK;
}
#else // SQUARING DISABLED
#ifdef USE_I2S_OUT
// Set stepper pulse output pins
inline __attribute__((always_inline)) IRAM_ATTR static void i2s_set_step_outputs (axes_signals_t step_outbits)
{
step_outbits.value ^= settings.steppers.step_invert.mask;
DIGITAL_OUT(X_STEP_PIN, step_outbits.x);
DIGITAL_OUT(Y_STEP_PIN, step_outbits.y);
DIGITAL_OUT(Z_STEP_PIN, step_outbits.z);
#ifdef X2_STEP_PIN
DIGITAL_OUT(X_STEP_PIN, step_outbits.x);
#endif
#ifdef Y2_STEP_PIN
DIGITAL_OUT(X_STEP_PIN, step_outbits.y);
#endif
#ifdef Z2_STEP_PIN
DIGITAL_OUT(X_STEP_PIN, step_outbits.z);
#endif
#ifdef A_AXIS
DIGITAL_OUT(A_STEP_PIN, step_outbits.a);
#endif
#ifdef B_AXIS
DIGITAL_OUT(B_STEP_PIN, step_outbits.b);
#endif
#ifdef C_AXIS
DIGITAL_OUT(C_STEP_PIN, step_outbits.c);
#endif
}
#else
// Set stepper pulse output pins
inline IRAM_ATTR static void set_step_outputs (axes_signals_t step_outbits)
{
if(step_outbits.x) {
RMT.conf_ch[X_AXIS].conf1.mem_rd_rst = 1;
RMT.conf_ch[X_AXIS].conf1.tx_start = 1;
}
if(step_outbits.y) {
RMT.conf_ch[Y_AXIS].conf1.mem_rd_rst = 1;
RMT.conf_ch[Y_AXIS].conf1.tx_start = 1;
}
if(step_outbits.z) {
RMT.conf_ch[Z_AXIS].conf1.mem_rd_rst = 1;
RMT.conf_ch[Z_AXIS].conf1.tx_start = 1;
}
#ifdef X2_STEP_PIN
if(step_outbits.x) {
RMT.conf_ch[X2_MOTOR].conf1.mem_rd_rst = 1;
RMT.conf_ch[X2_MOTOR].conf1.tx_start = 1;
}
#endif
#ifdef Y2_STEP_PIN
if(step_outbits.y) {
RMT.conf_ch[Y2_MOTOR].conf1.mem_rd_rst = 1;
RMT.conf_ch[Y2_MOTOR].conf1.tx_start = 1;
}
#endif
#ifdef Z2_STEP_PIN
if(step_outbits.z) {
RMT.conf_ch[Z2_MOTOR].conf1.mem_rd_rst = 1;
RMT.conf_ch[Z2_MOTOR].conf1.tx_start = 1;
}
#endif
#ifdef A_STEP_PIN
if(step_outbits.a) {
RMT.conf_ch[A_AXIS].conf1.mem_rd_rst = 1;
RMT.conf_ch[A_AXIS].conf1.tx_start = 1;
}
#endif
#ifdef B_STEP_PIN
if(step_outbits.b) {
RMT.conf_ch[B_AXIS].conf1.mem_rd_rst = 1;
RMT.conf_ch[B_AXIS].conf1.tx_start = 1;
}
#endif
#ifdef C_STEP_PIN
if(step_outbits.c) {
RMT.conf_ch[C_AXIS].conf1.mem_rd_rst = 1;
RMT.conf_ch[C_AXIS].conf1.tx_start = 1;
}
#endif
}
#endif // RMT Stepping
#endif // SQUARING DISABLED
#ifdef GANGING_ENABLED
static axes_signals_t getGangedAxes (bool auto_squared)
{
axes_signals_t ganged = {0};
if(auto_squared) {
#if X_AUTO_SQUARE
ganged.x = On;
#endif
#if Y_AUTO_SQUARE
ganged.y = On;
#endif
#if Z_AUTO_SQUARE
ganged.z = On;
#endif
} else {
#if X_GANGED
ganged.x = On;
#endif
#if Y_GANGED
ganged.y = On;
#endif
#if Z_GANGED
ganged.z = On;
#endif
}
return ganged;
}
#endif // GANGING_ENABLED
// Set stepper direction output pins
// NOTE: see note for set_step_outputs()
inline IRAM_ATTR static void set_dir_outputs (axes_signals_t dir_outbits)
{
dir_outbits.value ^= settings.steppers.dir_invert.mask;
DIGITAL_OUT(X_DIRECTION_PIN, dir_outbits.x);
DIGITAL_OUT(Y_DIRECTION_PIN, dir_outbits.y);
DIGITAL_OUT(Z_DIRECTION_PIN, dir_outbits.z);
#ifdef A_AXIS
DIGITAL_OUT(A_DIRECTION_PIN, dir_outbits.a);
#endif
#ifdef B_AXIS
DIGITAL_OUT(B_DIRECTION_PIN, dir_outbits.b);
#endif
#ifdef C_AXIS
DIGITAL_OUT(C_DIRECTION_PIN, dir_outbits.c);
#endif
#ifdef GANGING_ENABLED
dir_outbits.mask ^= settings.steppers.ganged_dir_invert.mask;
#ifdef X2_DIRECTION_PIN
DIGITAL_OUT(X2_DIRECTION_PIN, dir_outbits.x);
#endif
#ifdef Y2_DIRECTION_PIN
DIGITAL_OUT(Y2_DIRECTION_PIN, dir_outbits.y);
#endif
#ifdef Z2_DIRECTION_PIN
DIGITAL_OUT(Z2_DIRECTION_PIN, dir_outbits.z);
#endif
#endif
}
// Sets stepper direction and pulse pins and starts a step pulse
IRAM_ATTR static void stepperPulseStart (stepper_t *stepper)
{
if(stepper->dir_change)
set_dir_outputs(stepper->dir_outbits);
if(stepper->step_outbits.value) {
#ifdef USE_I2S_OUT
uint64_t step_pulse_start_time = esp_timer_get_time();
i2s_set_step_outputs(stepper->step_outbits);
while (esp_timer_get_time() - step_pulse_start_time < i2s_step_length) {
__asm__ __volatile__ ("nop"); // spin here until time to turn off step
}
i2s_set_step_outputs((axes_signals_t){0});
#else
set_step_outputs(stepper->step_outbits);
#endif
}
}
// Disables stepper driver interrupt
IRAM_ATTR static void stepperGoIdle (bool clear_signals)
{
TIMERG0.hw_timer[STEP_TIMER_INDEX].config.enable = 0;
if(clear_signals) {
#ifdef USE_I2S_OUT
i2s_set_step_outputs((axes_signals_t){0});
#else
set_step_outputs((axes_signals_t){0});
#endif
set_dir_outputs((axes_signals_t){0});
}
}
#ifdef USE_I2S_OUT
IRAM_ATTR static void I2S_stepperGoIdle (bool clear_signals)
{
if(clear_signals) {
i2s_set_step_outputs((axes_signals_t){0});
set_dir_outputs((axes_signals_t){0});
i2s_out_reset();
}
i2s_out_set_passthrough();
}
static void i2s_set_streaming_mode (bool stream)
{
if(!stream && hal.stepper.wake_up == I2S_stepperWakeUp) {
i2s_out_set_passthrough();
i2s_out_delay();
}
if(stream) {
hal.stepper.wake_up = I2S_stepperWakeUp;
hal.stepper.go_idle = I2S_stepperGoIdle;
hal.stepper.cycles_per_tick = I2S_stepperCyclesPerTick;
hal.stepper.pulse_start = I2S_stepperPulseStart;
} else {
hal.stepper.wake_up = stepperWakeUp;
hal.stepper.go_idle = stepperGoIdle;
hal.stepper.cycles_per_tick = stepperCyclesPerTick;
hal.stepper.pulse_start = stepperPulseStart;
}
}
#endif
// Enable/disable limit pins interrupt
static void limitsEnable (bool on, bool homing)
{
#ifdef USE_I2S_OUT
i2s_set_streaming_mode(!homing);
#endif
uint32_t i = sizeof(inputpin) / sizeof(input_signal_t);
do {
if(inputpin[--i].group == PinGroup_Limit) {
gpio_set_intr_type(inputpin[i].pin, on ? inputpin[i].intr_type : GPIO_INTR_DISABLE);
if(on)
gpio_intr_enable(inputpin[i].pin);
else
gpio_intr_disable(inputpin[i].pin);
}
} while(i);
}
// Returns limit state as an axes_signals_t variable.
// Each bitfield bit indicates an axis limit, where triggered is 1 and not triggered is 0.
inline IRAM_ATTR static limit_signals_t limitsGetState()
{
limit_signals_t signals = {0};
#ifdef DUAL_LIMIT_SWITCHES
signals.min2.mask = settings.limits.invert.mask;
#endif
signals.min.x = gpio_get_level(X_LIMIT_PIN);
signals.min.y = gpio_get_level(Y_LIMIT_PIN);
signals.min.z = gpio_get_level(Z_LIMIT_PIN);
#ifdef A_LIMIT_PIN
signals.min.a = gpio_get_level(A_LIMIT_PIN);
#endif
#ifdef B_LIMIT_PIN
signals.min.b = gpio_get_level(B_LIMIT_PIN);
#endif
#ifdef C_LIMIT_PIN
signals.min.c = gpio_get_level(C_LIMIT_PIN);
#endif
#ifdef X2_LIMIT_PIN
signals.min2.x = gpio_get_level(X2_LIMIT_PIN);
#endif
#ifdef Y2_LIMIT_PIN
signals.min2.y = gpio_get_level(Y2_LIMIT_PIN);
#endif
#ifdef Z2_LIMIT_PIN
signals.min2.z = gpio_get_level(Z2_LIMIT_PIN);
#endif
if (settings.limits.invert.value) {
signals.min.value ^= settings.limits.invert.mask;
#ifdef DUAL_LIMIT_SWITCHES
signals.min2.mask ^= settings.limits.invert.mask;
#endif
}
return signals;
}
// Returns system state as a control_signals_t variable.
// Each bitfield bit indicates a control signal, where triggered is 1 and not triggered is 0.
inline IRAM_ATTR static control_signals_t systemGetState (void)
{
control_signals_t signals;
signals.value = settings.control_invert.value;
#ifdef RESET_PIN
signals.reset = gpio_get_level(RESET_PIN);
#endif
#ifdef FEED_HOLD_PIN
signals.feed_hold = gpio_get_level(FEED_HOLD_PIN);
#endif
#ifdef CYCLE_START_PIN
signals.cycle_start = gpio_get_level(CYCLE_START_PIN);
#endif
#ifdef ENABLE_SAFETY_DOOR_INPUT_PIN
signals.safety_door_ajar = gpio_get_level(SAFETY_DOOR_PIN);
#endif
if(settings.control_invert.value)
signals.value ^= settings.control_invert.value;
return signals;
}
#ifdef PROBE_PIN
// Sets up the probe pin invert mask to
// appropriately set the pin logic according to setting for normal-high/normal-low operation
// and the probing cycle modes for toward-workpiece/away-from-workpiece.
static void probeConfigure(bool is_probe_away, bool probing)
{
#ifdef USE_I2S_OUT
i2s_set_streaming_mode(!probing);
#endif
probe.triggered = Off;
probe.is_probing = probing;
probe.inverted = is_probe_away ? !settings.probe.invert_probe_pin : settings.probe.invert_probe_pin;
#if PROBE_ISR
gpio_set_intr_type(inputpin[INPUT_PROBE].pin, probe_invert ? GPIO_INTR_NEGEDGE : GPIO_INTR_POSEDGE);
inputpin[INPUT_PROBE].active = false;
#endif
}
// Returns the probe connected and triggered pin states.
probe_state_t probeGetState (void)
{
probe_state_t state = {0};
state.connected = probe.connected;
#if PROBE_ISR
// TODO: verify!
inputpin[INPUT_PROBE].active = inputpin[INPUT_PROBE].active || ((uint8_t)gpio_get_level(PROBE_PIN) ^ probe.inverted);
state.triggered = inputpin[INPUT_PROBE].active;
#else
state.triggered = (uint8_t)gpio_get_level(PROBE_PIN) ^ probe.inverted;
#endif
return state;
}
#endif
#if VFD_SPINDLE != 1
// Static spindle (off, on cw & on ccw)
IRAM_ATTR inline static void spindle_off (void)
{
#if IOEXPAND_ENABLE
iopins.spindle_on = settings.spindle.invert.on ? On : Off;
ioexpand_out(iopins);
#else
gpio_set_level(SPINDLE_ENABLE_PIN, settings.spindle.invert.on ? 1 : 0);
#endif
}