-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathdriver.c
2150 lines (1741 loc) · 72.5 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 - driver code for Texas Instruments MSP432P401R ARM processor
Part of grblHAL
Copyright (c) 2017-2025 Terje Io
grblHAL 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.
grblHAL 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 grblHAL. If not, see <http://www.gnu.org/licenses/>.
*/
#include <math.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include "driver.h"
#include "serial.h"
#define AUX_DEVICES // until all drivers are converted?
#ifndef AUX_CONTROLS
#define AUX_CONTROLS (AUX_CONTROL_SPINDLE|AUX_CONTROL_COOLANT)
#endif
#include "grbl/task.h"
#include "grbl/machine_limits.h"
#include "grbl/spindle_sync.h"
#include "grbl/state_machine.h"
#include "grbl/motor_pins.h"
#include "grbl/pin_bits_masks.h"
#if I2C_ENABLE
#include "i2c.h"
#endif
#if EEPROM_ENABLE
#include "eeprom/eeprom.h"
#endif
#if ATC_ENABLE
#include "atc.h"
#endif
#if DRIVER_SPINDLE_ENABLE
static spindle_id_t spindle_id = -1;
#if DRIVER_SPINDLE_ENABLE & SPINDLE_PWM
static spindle_pwm_t spindle_pwm;
#endif // DRIVER_SPINDLE_ENABLE & SPINDLE_PWM
#endif // DRIVER_SPINDLE_ENABLE
#ifdef SPINDLE_RPM_CONTROLLED
typedef enum {
PIDState_Disabled = 0,
PIDState_Pending,
PIDState_Active,
} pid_state_t;
// PID data for closed loop spindle RPM control
typedef struct {
pid_state_t pid_state;
pidf_t pid;
bool pid_enabled;
float rpm;
} spindle_control_t;
static volatile uint32_t pid_count = 0;
static spindle_control_t spindle_control = { .pid_state = PIDState_Disabled, .pid = {0}};
#endif // SPINDLE_RPM_CONTROLLED
#if AUX_CONTROLS_ENABLED
static uint8_t probe_port;
static void aux_irq_handler (uint8_t port, bool state);
#endif
static pin_debounce_t debounce;
static periph_signal_t *periph_pins = NULL;
static input_signal_t inputpin[] = {
#if ESTOP_ENABLE
{ .id = Input_EStop, .port = RESET_PORT, .pin = RESET_PIN, .group = PinGroup_Control },
#else
{ .id = Input_Reset, .port = RESET_PORT, .pin = RESET_PIN, .group = PinGroup_Control },
#endif
{ .id = Input_FeedHold, .port = FEED_HOLD_PORT, .pin = FEED_HOLD_PIN, .group = PinGroup_Control },
{ .id = Input_CycleStart, .port = CYCLE_START_PORT, .pin = CYCLE_START_PIN, .group = PinGroup_Control },
// Limit input pins must be consecutive in this array
{ .id = Input_LimitX, .port = LIMIT_PORT_X, .pin = X_LIMIT_PIN, .group = PinGroup_Limit },
{ .id = Input_LimitY, .port = LIMIT_PORT_Y, .pin = Y_LIMIT_PIN, .group = PinGroup_Limit },
{ .id = Input_LimitZ, .port = LIMIT_PORT_Z, .pin = Z_LIMIT_PIN, .group = PinGroup_Limit }
#ifdef A_LIMIT_PIN
, { .id = Input_LimitA, .port = LIMIT_PORT_A, .pin = A_LIMIT_PIN, .group = PinGroup_Limit }
#endif
#ifdef B_LIMIT_PIN
, { .id = Input_LimitB, .port = LIMIT_PORT_B, .pin = B_LIMIT_PIN, .group = PinGroup_Limit }
#endif
#ifdef C_LIMIT_PIN
, { .id = Input_LimitC, .port = LIMIT_PORT_C, .pin = C_LIMIT_PIN, .group = PinGroup_Limit }
#endif
#if LIMITS_OVERRIDE_BIT
, { .id = Input_LimitsOverride, .port = LIMITS_OVERRIDE_PORT, .pin = LIMITS_OVERRIDE_PIN, .group = PinGroup_Limit }
#endif
#if SPINDLE_ENCODER_ENABLE
, { .id = Input_SpindleIndex, .port = SPINDLE_INDEX_PORT, .pin = SPINDLE_INDEX_PIN, .group = PinGroup_QEI_Index }
#endif
// Aux input pins must be consecutive in this array
#ifdef AUXINPUT0_PIN
, { .id = Input_Aux0, .port = AUXINPUT0_PORT, .pin = AUXINPUT0_PIN, .group = PinGroup_AuxInput }
#endif
#ifdef AUXINPUT1_PIN
, { .id = Input_Aux1, .port = AUXINPUT1_PORT, .pin = AUXINPUT1_PIN, .group = PinGroup_AuxInput }
#endif
#ifdef AUXINPUT2_PIN
, { .id = Input_Aux2, .port = AUXINPUT2_PORT, .pin = AUXINPUT2_PIN, .group = PinGroup_AuxInput }
#endif
#ifdef AUXINPUT3_PIN
, { .id = Input_Aux3, .port = AUXINPUT3_PORT, .pin = AUXINPUT3_PIN, .group = PinGroup_AuxInput }
#endif
#ifdef AUXINPUT4_PIN
, { .id = Input_Aux4, .port = AUXINPUT4_PORT, .pin = AUXINPUT4_PIN, .group = PinGroup_AuxInput }
#endif
#ifdef AUXINPUT5_PIN
, { .id = Input_Aux5, .port = AUXINPUT5_PORT, .pin = AUXINPUT5_PIN, .group = PinGroup_AuxInput }
#endif
#ifdef AUXINPUT6_PIN
, { .id = Input_Aux6, .port = AUXINPUT6_PORT, .pin = AUXINPUT6_PIN, .group = PinGroup_AuxInput }
#endif
};
static output_signal_t outputpin[] = {
{ .id = Output_StepX, .port = X_STEP_PORT, .pin = X_STEP_PIN, .group = PinGroup_StepperStep },
{ .id = Output_StepY, .port = Y_STEP_PORT, .pin = Y_STEP_PIN, .group = PinGroup_StepperStep },
{ .id = Output_StepZ, .port = Z_STEP_PORT, .pin = Z_STEP_PIN, .group = PinGroup_StepperStep },
#ifdef A_AXIS
{ .id = Output_StepA, .port = A_STEP_PORT, .pin = A_STEP_PIN, .group = PinGroup_StepperStep },
#endif
#ifdef B_AXIS
{ .id = Output_StepB, .port = B_STEP_PORT, .pin = B_STEP_PIN, .group = PinGroup_StepperStep },
#endif
#ifdef C_AXIS
{ .id = Output_StepC, .port = B_STEP_PORT, .pin = C_STEP_PIN, .group = PinGroup_StepperStep },
#endif
{ .id = Output_DirX, .port = X_DIRECTION_PORT, .pin = X_DIRECTION_PIN, .group = PinGroup_StepperDir },
{ .id = Output_DirY, .port = Y_DIRECTION_PORT, .pin = Y_DIRECTION_PIN, .group = PinGroup_StepperDir },
{ .id = Output_DirZ, .port = Z_DIRECTION_PORT, .pin = Z_DIRECTION_PIN, .group = PinGroup_StepperDir },
#ifdef A_AXIS
{ .id = Output_DirA, .port = A_DIRECTION_PORT, .pin = A_DIRECTION_PIN, .group = PinGroup_StepperDir },
#endif
#ifdef B_AXIS
{ .id = Output_DirB, .port = B_DIRECTION_PORT, .pin = B_DIRECTION_PIN, .group = PinGroup_StepperDir },
#endif
#ifdef C_AXIS
{ .id = Output_DirC, .port = C_DIRECTION_PORT, .pin = C_DIRECTION_PIN, .group = PinGroup_StepperDir },
#endif
#if CNC_BOOSTERPACK_A4998
{ .id = Output_StepperPower, .port = STEPPERS_VDD_PORT, .pin = STEPPERS_VDD_PIN, .group = PinGroup_StepperPower },
#endif
#if !TRINAMIC_MOTOR_ENABLE
#ifdef STEPPERS_ENABLE_PORT
{ .id = Output_StepperEnable, .port = STEPPERS_ENABLE_PORT, .pin = STEPPERS_ENABLE_PIN, .group = PinGroup_StepperEnable },
#endif
#ifdef XY_ENABLE_PORT
{ .id = Output_StepperEnableXY, .port = XY_ENABLE_PORT, .pin = XY_ENABLE_PIN, .group = PinGroup_StepperEnable },
#endif
#ifdef Z_ENABLE_PORT
{ .id = Output_StepperEnableZ, .port = Z_ENABLE_PORT, .pin = Z_ENABLE_PIN, .group = PinGroup_StepperEnable },
#endif
#ifdef A_ENABLE_PORT
{ .id = Output_StepperEnableA, .port = A_ENABLE_PORT, .pin = A_ENABLE_PIN, .group = PinGroup_StepperEnable, },
#endif
#ifdef B_ENABLE_PORT
{ .id = Output_StepperEnableB, .port = B_ENABLE_PORT, .pin = B_ENABLE_PIN, .group = PinGroup_StepperEnable, },
#endif
#ifdef C_ENABLE_PORT
{ .id = Output_StepperEnableC, .port = C_ENABLE_PORT, .pin = C_ENABLE_PIN, .group = PinGroup_StepperEnable, },
#endif
#endif // !TRINAMIC_MOTOR_ENABLE
#if !(AUX_CONTROLS & AUX_CONTROL_SPINDLE)
#if DRIVER_SPINDLE_ENABLE
{ .id = Output_SpindleOn, .port = SPINDLE_ENABLE_PORT, .pin = SPINDLE_ENABLE_PIN, .group = PinGroup_SpindleControl },
{ .id = Output_SpindleDir, .port = SPINDLE_DIRECTION_PORT, .pin = SPINDLE_DIRECTION_PIN, .group = PinGroup_SpindleControl },
#endif
#endif
#if !(AUX_CONTROLS & AUX_CONTROL_COOLANT)
{ .id = Output_CoolantFlood, .port = COOLANT_FLOOD_PORT, .pin = COOLANT_FLOOD_PIN, .group = PinGroup_Coolant },
{ .id = Output_CoolantMist, .port = COOLANT_MIST_PORT, .pin = COOLANT_MIST_PIN, .group = PinGroup_Coolant },
#endif
#ifdef RTS_PIN
{ .id = Output_RTS, .port = RTS_PORT, .pin = RTS_PIN, .group = PinGroup_UART },
#endif
#ifdef AUXOUTPUT0_PORT
{ .id = Output_Aux0, .port = AUXOUTPUT0_PORT, .pin = AUXOUTPUT0_PIN, .group = PinGroup_AuxOutput },
#endif
#ifdef AUXOUTPUT1_PORT
{ .id = Output_Aux1, .port = AUXOUTPUT1_PORT, .pin = AUXOUTPUT1_PIN, .group = PinGroup_AuxOutput },
#endif
#ifdef AUXOUTPUT2_PORT
{ .id = Output_Aux2, .port = AUXOUTPUT2_PORT, .pin = AUXOUTPUT2_PIN, .group = PinGroup_AuxOutput },
#endif
#ifdef AUXOUTPUT3_PORT
{ .id = Output_Aux3, .port = AUXOUTPUT3_PORT, .pin = AUXOUTPUT3_PIN, .group = PinGroup_AuxOutput },
#endif
#ifdef AUXOUTPUT4_PORT
{ .id = Output_Aux4, .port = AUXOUTPUT4_PORT, .pin = AUXOUTPUT4_PIN, .group = PinGroup_AuxOutput },
#endif
#ifdef AUXOUTPUT5_PORT
{ .id = Output_Aux5, .port = AUXOUTPUT5_PORT, .pin = AUXOUTPUT5_PIN, .group = PinGroup_AuxOutput },
#endif
#ifdef AUXOUTPUT6_PORT
{ .id = Output_Aux6, .port = AUXOUTPUT6_PORT, .pin = AUXOUTPUT6_PIN, .group = PinGroup_AuxOutput },
#endif
#ifdef AUXOUTPUT7_PORT
{ .id = Output_Aux7, .port = AUXOUTPUT7_PORT, .pin = AUXOUTPUT7_PIN, .group = PinGroup_AuxOutput }
#endif
#ifdef AUXOUTPUT0_ANALOG_PORT
{ .id = Output_Analog_Aux0, .port = AUXOUTPUT0_ANALOG_PORT, .pin = AUXOUTPUT0_ANALOG_PIN, .group = PinGroup_AuxOutputAnalog },
#elif defined(AUXOUTPUT0_PWM_PORT)
{ .id = Output_Analog_Aux0, .port = AUXOUTPUT0_PWM_PORT, .pin = AUXOUTPUT0_PWM_PIN, .group = PinGroup_AuxOutputAnalog, .mode = { PINMODE_PWM } },
#endif
#ifdef AUXOUTPUT1_ANALOG_PORT
{ .id = Output_Analog_Aux1, .port = AUXOUTPUT1_ANALOG_PORT, .pin = AUXOUTPUT1_ANALOG_PIN, .group = PinGroup_AuxOutputAnalog }
#elif defined(AUXOUTPUT1_PWM_PORT)
{ .id = Output_Analog_Aux1, .port = AUXOUTPUT1_PWM_PORT, .pin = AUXOUTPUT1_PWM_PIN, .group = PinGroup_AuxOutputAnalog, .mode = { PINMODE_PWM } }
#endif
};
static pin_group_pins_t limit_inputs = {0};
static input_signal_t *p1_pins[9], *p2_pins[9], *p3_pins[9], *p4_pins[9], *p5_pins[9], *p6_pins[9];
static volatile bool spindleLock = false;
static bool IOInitDone = false;
// Inverts the probe pin state depending on user settings and probing cycle mode.
static uint16_t pulse_length;
static volatile uint32_t elapsed_tics = 0;
static axes_signals_t next_step_out;
#if SPINDLE_ENCODER_ENABLE
static spindle_data_t spindle_data;
static spindle_encoder_t spindle_encoder = {
.tics_per_irq = 4
};
static on_spindle_programmed_ptr on_spindle_programmed = NULL;
#ifndef SPINDLE_PULSE_BIT
#define SPINDLE_PULSE_BIT (1<<SPINDLE_PULSE_PIN)
#endif
#endif
static delay_t delay = { .ms = 1, .callback = NULL }; // NOTE: initial ms set to 1 for "resetting" systick timer on startup
static probe_state_t probe = {
.connected = On
};
#include "grbl/stepdir_map.h"
#if SPINDLE_ENCODER_ENABLE
static void stepperPulseStartSynchronized (stepper_t *stepper);
#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
// LinuxCNC example settings
// MAX_OUTPUT = 300 DEADBAND = 0.0 P = 3 I = 1.0 D = 0.1 FF0 = 0.0 FF1 = 0.1 FF2 = 0.0 BIAS = 0.0 MAXI = 20.0 MAXD = 20.0 MAXERROR = 250.0
//
// You will always get oscillation on a PID system if you increase any P,I,D term too high
// I would try using less P (say 2) and then see how high an I term you can have and stay stable
// D term should not be needed
static void driver_delay_ms (uint32_t ms, void (*callback)(void))
{
// while(delay.callback);
if((delay.ms = ms) > 0) {
if(!(delay.callback = callback)) {
while(delay.ms)
grbl.on_execute_delay(state_get());
}
} else if(callback)
callback();
}
// Set stepper pulse output pins
// NOTE: step_outbits are: bit0 -> X, bit1 -> Y, bit2 -> Z...
// Mapping to registers can be done by
// 1. bitbanding. Pros: can assign pins to different ports, no RMW needed. Cons: overhead, pin changes not synchronous
// 2. bit shift. Pros: fast, Cons: bits must be consecutive
// 3. lookup table. Pros: signal inversions done at setup, Cons: slower than bit shift
inline __attribute__((always_inline)) static void set_step_outputs (axes_signals_t step_outbits)
{
#if STEP_OUTMODE == GPIO_BITBAND
step_outbits.value ^= settings.steppers.step_invert.mask;
BITBAND_PERI(STEP_PORT->OUT, X_STEP_PIN) = step_outbits.x;
BITBAND_PERI(STEP_PORT->OUT, Y_STEP_PIN) = step_outbits.y;
BITBAND_PERI(STEP_PORT->OUT, Z_STEP_PIN) = step_outbits.z;
#elif STEP_OUTMODE == GPIO_MAP
STEP_PORT->OUT = (STEP_PORT->OUT & ~STEP_MASK) | step_outmap[step_outbits.value];
#else
STEP_PORT->OUT = (STEP_PORT->OUT & ~STEP_MASK) | ((step_outbits.value << STEP_OUTMODE) ^ settings.steppers.step_invert.mask);
#endif
}
// Set stepper direction output pins
// NOTE: see note for set_step_outputs()
/*inline __attribute__((always_inline))*/ static void set_dir_outputs (axes_signals_t dir_outbits)
{
#if DIRECTION_OUTMODE == GPIO_BITBAND
dir_outbits.value ^= settings.steppers.dir_invert.mask;
BITBAND_PERI(DIRECTION_PORT->OUT, X_DIRECTION_PIN) = dir_outbits.x;
BITBAND_PERI(DIRECTION_PORT->OUT, Y_DIRECTION_PIN) = dir_outbits.y;
BITBAND_PERI(DIRECTION_PORT->OUT, Z_DIRECTION_PIN) = dir_outbits.z;
#elif DIRECTION_OUTMODE == GPIO_MAP
DIRECTION_PORT->OUT = (DIRECTION_PORT->OUT & ~DIRECTION_MASK) | dir_outmap[dir_outbits.value];
#else
DIRECTION_PORT->OUT = (DIRECTION_PORT->OUT & ~DIRECTION_MASK) | ((dir_outbits.value << DIRECTION_OUTMODE) ^ settings.steppers.dir_invert.mask);
#endif
}
// Enable/disable stepper motors
static void stepperEnable (axes_signals_t enable, bool hold)
{
enable.value ^= settings.steppers.enable_invert.mask;
#if TRINAMIC_MOTOR_ENABLE
axes_signals_t tmc_enable = trinamic_stepper_enable(enable);
#if !CNC_BOOSTERPACK // Trinamic BoosterPack does not support mixed drivers
if(!tmc_enable.z)
BITBAND_PERI(Z_ENABLE_PORT->OUT, Z_ENABLE_PIN) = enable.z;
if(!tmc_enable.x)
BITBAND_PERI(XY_ENABLE_PORT->OUT, STEPPERS_ENABLE_X_PIN) = enable.x;
#endif
#else
BITBAND_PERI(Z_ENABLE_PORT->OUT, Z_ENABLE_PIN) = enable.z;
BITBAND_PERI(XY_ENABLE_PORT->OUT, XY_ENABLE_PIN) = enable.x;
#endif
}
// Starts stepper driver ISR timer and forces a stepper driver interrupt callback
static void stepperWakeUp (void)
{
hal.stepper.enable((axes_signals_t){AXES_BITMASK}, false);
STEPPER_TIMER->LOAD = hal.f_step_timer / 500; // ~2ms delay to allow drivers time to wake up.
STEPPER_TIMER->CONTROL |= TIMER32_CONTROL_ENABLE|TIMER32_CONTROL_IE;
}
// Disables stepper driver interrupts
static void stepperGoIdle (bool clear_signals)
{
STEPPER_TIMER->CONTROL &= ~(TIMER32_CONTROL_ENABLE|TIMER32_CONTROL_IE);
STEPPER_TIMER->INTCLR = 0;
if(clear_signals) {
set_step_outputs((axes_signals_t){0});
set_dir_outputs((axes_signals_t){0});
}
}
static void stepperPulseStartDelayed (stepper_t *stepper);
// Sets up stepper driver interrupt timeout, limiting the slowest speed
static void stepperCyclesPerTick (uint32_t cycles_per_tick)
{
STEPPER_TIMER->LOAD = cycles_per_tick < (1UL << 20) ? cycles_per_tick : 0x000FFFFFUL;
}
// "Normal" version: Sets stepper direction and pulse pins and starts a step pulse a few nanoseconds later.
// If spindle synchronized motion switch to PID version.
static void stepperPulseStart (stepper_t *stepper)
{
if(stepper->dir_changed.bits) {
stepper->dir_changed.bits = 0;
set_dir_outputs(stepper->dir_out);
}
if(stepper->step_out.bits) {
set_step_outputs(stepper->step_out);
PULSE_TIMER->CTL |= TIMER_A_CTL_CLR|TIMER_A_CTL_MC1;
}
}
// Delayed pulse version: sets stepper direction and pulse pins and starts a step pulse with an initial delay.
// If spindle synchronized motion switch to PID version.
static void stepperPulseStartDelayed (stepper_t *stepper)
{
if(stepper->dir_changed.bits) {
set_dir_outputs(stepper->dir_out);
if(stepper->step_out.bits) {
if(stepper->step_out.bits & stepper->dir_changed.bits) {
next_step_out = stepper->step_out; // Store out_bits
PULSE_TIMER->CCR[0] = 0;
PULSE_TIMER->CCTL[1] &= ~TIMER_A_CCTLN_CCIFG; // Clear and
PULSE_TIMER->CCTL[1] |= TIMER_A_CCTLN_CCIE; // enable CCR1 interrupt
PULSE_TIMER->CTL |= TIMER_A_CTL_CLR|TIMER_A_CTL_MC1;
} else {
set_step_outputs(stepper->step_out);
PULSE_TIMER->CTL |= TIMER_A_CTL_CLR|TIMER_A_CTL_MC1;
}
}
stepper->dir_changed.bits = 0;
return;
}
if(stepper->step_out.bits) {
set_step_outputs(stepper->step_out);
PULSE_TIMER->CTL |= TIMER_A_CTL_CLR|TIMER_A_CTL_MC1;
}
}
// Enable/disable limit pins interrupt
static void limitsEnable (bool on, axes_signals_t homing_cycle)
{
bool disable = !on;
axes_signals_t pin;
input_signal_t *limit;
uint_fast8_t idx = limit_inputs.n_pins;
limit_signals_t homing_source = xbar_get_homing_source_from_cycle(homing_cycle);
do {
limit = &limit_inputs.pins.inputs[--idx];
if(limit->group & (PinGroup_Limit|PinGroup_LimitMax)) {
if(on && homing_cycle.mask) {
pin = xbar_fn_to_axismask(limit->id);
disable = limit->group == PinGroup_Limit ? (pin.mask & homing_source.min.mask) : (pin.mask & homing_source.max.mask);
}
BITBAND_PERI(limit->port->IFG, limit->pin) = 0;
BITBAND_PERI(limit->port->IE, limit->pin) = !disable;
}
} while(idx);
}
// 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 static limit_signals_t limitsGetState (void)
{
limit_signals_t signals = {0};
signals.min.x = BITBAND_PERI(LIMIT_PORT_X->IN, X_LIMIT_PIN);
signals.min.y = BITBAND_PERI(LIMIT_PORT_Y->IN, Y_LIMIT_PIN);
signals.min.z = BITBAND_PERI(LIMIT_PORT_Z->IN, Z_LIMIT_PIN);
if (settings.limits.invert.mask)
signals.min.value ^= settings.limits.invert.mask;
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.
static control_signals_t systemGetState (void)
{
control_signals_t signals;
signals.value = settings.control_invert.mask;
#if ESTOP_ENABLE
signals.e_stop = BITBAND_PERI(RESET_PORT->IN, RESET_PIN);
#else
signals.reset = BITBAND_PERI(RESET_PORT->IN, RESET_PIN);
#endif
signals.feed_hold = BITBAND_PERI(FEED_HOLD_PORT->IN, FEED_HOLD_PIN);
signals.cycle_start = BITBAND_PERI(CYCLE_START_PORT->IN, CYCLE_START_PIN);
#if SAFETY_DOOR_BIT
signals.safety_door_ajar = BITBAND_PERI(SAFETY_DOOR_PORT->IN, SAFETY_DOOR_PIN);
#endif
#if AUX_CONTROLS_ENABLED
#ifdef SAFETY_DOOR_PIN
if(debounce.safety_door)
signals.safety_door_ajar = !settings.control_invert.safety_door_ajar;
else
signals.safety_door_ajar = BITBAND_PERI(SAFETY_DOOR_PORT->IN, SAFETY_DOOR_PIN);
#endif
#ifdef MOTOR_FAULT_PIN
signals.motor_fault = BITBAND_PERI(MOTOR_FAULT_PORT->IN, MOTOR_FAULT_PIN);
#endif
#ifdef MOTOR_WARNING_PIN
signals.motor_warning = BITBAND_PERI(MOTOR_WARNING_PORT->IN, MOTOR_WARNING_PIN);
#endif
if(settings.control_invert.mask)
signals.value ^= settings.control_invert.mask;
#if AUX_CONTROLS_SCAN
uint_fast8_t i;
for(i = AUX_CONTROLS_SCAN; i < AuxCtrl_NumEntries; i++) {
if(aux_ctrl[i].enabled) {
signals.mask &= ~aux_ctrl[i].cap.mask;
if(hal.port.wait_on_input(Port_Digital, aux_ctrl[i].port, WaitMode_Immediate, 0.0f) == 1)
signals.mask |= aux_ctrl[i].cap.mask;
}
}
#endif
#else
if(settings.control_invert.mask)
signals.value ^= settings.control_invert.mask;
#endif // AUX_CONTROLS_ENABLED
return signals;
}
#if PROBE_ENABLE
// Toggle probe connected status. Used when no input pin is available.
static void probeConnectedToggle (void)
{
probe.connected = !probe.connected;
}
// 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)
{
probe.inverted = is_probe_away ? !settings.probe.invert_probe_pin : settings.probe.invert_probe_pin;
if(hal.driver_cap.probe_latch) {
probe.is_probing = Off;
probe.triggered = hal.probe.get_state().triggered;
pin_irq_mode_t irq_mode = probing && !probe.triggered ? (probe.inverted ? IRQ_Mode_Falling : IRQ_Mode_Rising) : IRQ_Mode_None;
probe.irq_enabled = hal.port.register_interrupt_handler(probe_port, irq_mode, aux_irq_handler) && irq_mode != IRQ_Mode_None;
}
if(!probe.irq_enabled)
probe.triggered = Off;
probe.is_probing = probing;
}
// Returns the probe pin state. Triggered = true.
static probe_state_t probeGetState (void)
{
probe_state_t state = {0};
state.connected = probe.connected;
state.triggered = probe.is_probing && probe.irq_enabled ? probe.triggered : BITBAND_PERI(PROBE_PORT->IN, PROBE_PIN) ^ probe.inverted;
return state;
}
#endif // PROBE_ENABLE
#if MPG_ENABLE == 1
static void mpg_select (void *data)
{
stream_mpg_enable(BITBAND_PERI(MPG_MODE_PORT->IN, MPG_MODE_PIN) == 0);
BITBAND_PERI(MPG_MODE_PORT->IES, MPG_MODE_PIN) = !sys.mpg_mode;
BITBAND_PERI(MPG_MODE_PORT->IFG, MPG_MODE_PIN) = 0;
BITBAND_PERI(MPG_MODE_PORT->IE, MPG_MODE_PIN) = 1;
}
static void mpg_enable (void *data)
{
bool on = BITBAND_PERI(MPG_MODE_PORT->IN, MPG_MODE_PIN) == 0;
if(sys.mpg_mode == (BITBAND_PERI(MPG_MODE_PORT->IN, MPG_MODE_PIN) == 0))
mpg_select(data);
#if I2C_STROBE_ENABLE
BITBAND_PERI(I2C_STROBE_PORT->IE, I2C_STROBE_PIN) = 1;
#endif
}
#endif // MPG_ENABLE == 1
#if AUX_CONTROLS_ENABLED
static void aux_irq_handler (uint8_t port, bool state)
{
aux_ctrl_t *pin;
control_signals_t signals = {0};
if((pin = aux_ctrl_get_pin(port))) {
switch(pin->function) {
#ifdef PROBE_PIN
case Input_Probe:
if(probe.is_probing) {
probe.triggered = On;
return;
} else
signals.probe_triggered = On;
break;
#endif
#ifdef I2C_STROBE_PIN
case Input_I2CStrobe:
if(i2c_strobe.callback)
i2c_strobe.callback(0, DIGITAL_IN(I2C_STROBE_PORT, I2C_STROBE_PIN) == 0);
break;
#endif
#ifdef MPG_MODE_PIN
case Input_MPGSelect:
task_add_immediate(mpg_select, NULL);
break;
#endif
default:
break;
}
signals.mask |= pin->cap.mask;
if(pin->irq_mode == IRQ_Mode_Change && pin->function != Input_Probe)
signals.deasserted = hal.port.wait_on_input(Port_Digital, pin->aux_port, WaitMode_Immediate, 0.0f) == 0;
}
if(signals.mask) {
if(!signals.deasserted)
signals.mask |= systemGetState().mask;
hal.control.interrupt_callback(signals);
}
}
static bool aux_claim_explicit (aux_ctrl_t *aux_ctrl)
{
xbar_t *pin;
if((pin = ioport_claim(Port_Digital, Port_Input, &aux_ctrl->aux_port, NULL))) {
ioport_set_function(pin, aux_ctrl->function, &aux_ctrl->cap);
#ifdef PROBE_PIN
if(aux_ctrl->function == Input_Probe) {
probe_port = aux_ctrl->aux_port;
hal.probe.get_state = probeGetState;
hal.probe.configure = probeConfigure;
hal.probe.connected_toggle = probeConnectedToggle;
hal.driver_cap.probe_pull_up = On;
hal.signals_cap.probe_triggered = hal.driver_cap.probe_latch = (pin->cap.irq_mode & aux_ctrl->irq_mode) == aux_ctrl->irq_mode;
}
#endif
#if SAFETY_DOOR_ENABLE
if(aux_ctrl->function == Input_SafetyDoor)
((input_signal_t *)aux_ctrl->input)->mode.debounce = ((input_signal_t *)aux_ctrl->input)->cap.debounce = On;
#endif
} else
aux_ctrl->aux_port = 0xFF;
return aux_ctrl->aux_port != 0xFF;
}
#endif // AUX_CONTROLS_ENABLED
#if AUX_CONTROLS
bool aux_out_claim_explicit (aux_ctrl_out_t *aux_ctrl)
{
xbar_t *pin;
if((pin = ioport_claim(Port_Digital, Port_Output, &aux_ctrl->aux_port, NULL)))
ioport_set_function(pin, aux_ctrl->function, NULL);
else
aux_ctrl->aux_port = 0xFF;
return aux_ctrl->aux_port != 0xFF;
}
#endif // AUX_CONTROLS
#if SPINDLE_ENCODER_ENABLE
inline static float spindle_calc_rpm (uint32_t tpp)
{
return spindle_encoder.rpm_factor / (float)tpp;
}
#endif
#if DRIVER_SPINDLE_ENABLE
// Static spindle (off, on cw & on ccw)
inline static void spindle_off (spindle_ptrs_t *spindle)
{
spindle->context.pwm->flags.enable_out = Off;
#ifdef SPINDLE_DIRECTION_PIN
if(spindle->context.pwm->flags.cloned) {
BITBAND_PERI(SPINDLE_DIRECTION_PORT->OUT, SPINDLE_DIRECTION_PIN) = settings.pwm_spindle.invert.ccw;
} else {
BITBAND_PERI(SPINDLE_ENABLE_PORT->OUT, SPINDLE_ENABLE_PIN) = settings.pwm_spindle.invert.on;
}
#elif defined(SPINDLE_ENABLE_PIN)
BITBAND_PERI(SPINDLE_ENABLE_PORT->OUT, SPINDLE_ENABLE_PIN) = settings.pwm_spindle.invert.on;
BITBAND_PERI(SPINDLE_DIRECTION_PORT->OUT, SPINDLE_DIRECTION_PIN) = settings.pwm_spindle.invert.ccw;
#endif
}
inline static void spindle_on (spindle_ptrs_t *spindle)
{
#ifdef SPINDLE_DIRECTION_PIN
if(spindle->context.pwm->flags.cloned) {
BITBAND_PERI(SPINDLE_DIRECTION_PORT->OUT, SPINDLE_DIRECTION_PIN) = !settings.pwm_spindle.invert.ccw;
} else {
BITBAND_PERI(SPINDLE_ENABLE_PORT->OUT, SPINDLE_ENABLE_PIN) = !settings.pwm_spindle.invert.on;
}
#elif defined(SPINDLE_ENABLE_PIN)
BITBAND_PERI(SPINDLE_ENABLE_PORT->OUT, SPINDLE_ENABLE_PIN) = !settings.pwm_spindle.invert.on;
#endif
#if SPINDLE_ENCODER_ENABLE
if(!spindle->context.pwm->flags.enable_out && spindle->reset_data)
spindle->reset_data();
#endif
spindle->context.pwm->flags.enable_out = On;
}
inline static void spindle_dir (bool ccw)
{
BITBAND_PERI(SPINDLE_DIRECTION_PORT->OUT, SPINDLE_DIRECTION_PIN) = ccw ^ settings.pwm_spindle.invert.ccw;
}
// Start or stop spindle
static void spindleSetState (spindle_ptrs_t *spindle, spindle_state_t state, float rpm)
{
if(!state.on)
spindle_off(spindle);
else {
spindle_dir(state.ccw);
spindle_on(spindle);
}
}
#if DRIVER_SPINDLE_ENABLE & SPINDLE_PWM
// Variable spindle control functions
static void pwm_off (spindle_ptrs_t *spindle)
{
if(spindle->context.pwm->flags.always_on) {
SPINDLE_PWM_TIMER->CCR[2] = spindle->context.pwm->off_value;
SPINDLE_PWM_TIMER->CCTL[2] = settings.pwm_spindle.invert.pwm ? TIMER_A_CCTLN_OUTMOD_6 : TIMER_A_CCTLN_OUTMOD_2;
} else
SPINDLE_PWM_TIMER->CCTL[2] = settings.pwm_spindle.invert.pwm ? TIMER_A_CCTLN_OUT : 0; // Set PWM output according to invert setting
}
// Sets spindle speed
static void spindleSetSpeed (spindle_ptrs_t *spindle, uint_fast16_t pwm_value)
{
while(spindleLock); // wait for PID
if(pwm_value == spindle->context.pwm->off_value) {
if(spindle->context.pwm->flags.rpm_controlled) {
spindle_off(spindle);
if(spindle->context.pwm->flags.laser_off_overdrive)
SPINDLE_PWM_TIMER->CCR[2] = spindle->context.pwm->pwm_overdrive;
} else
pwm_off(spindle);
#ifdef SPINDLE_RPM_CONTROLLED
spindle_control.pid.error = 0.0f;
#endif
} else {
if(!spindle->context.pwm->flags.enable_out && spindle->context.pwm->flags.rpm_controlled)
spindle_on(spindle);
SPINDLE_PWM_TIMER->CCR[2] = pwm_value;
SPINDLE_PWM_TIMER->CCTL[2] = settings.pwm_spindle.invert.pwm ? TIMER_A_CCTLN_OUTMOD_6 : TIMER_A_CCTLN_OUTMOD_2;
}
}
#ifdef SPINDLE_RPM_CONTROLLED
// todo: remove?
static void spindleUpdateRPM (spindle_ptrs_t *spindle, float rpm)
{
while(spindleLock); // wait for PID
spindleSetSpeed(spindle->context.pwm->compute_value(spindle->context.pwm, rpm + spindle_control.pid.error, spindle_control.pid.error != 0.0f));
if(spindle->context.pwm->settings->at_speed_tolerance > 0.0f) {
spindle_data.rpm_low_limit = rpm / (1.0f + spindle->context.pwm->settings->at_speed_tolerance);
spindle_data.rpm_high_limit = rpm * (1.0f + spindle->context.pwm->settings->at_speed_tolerance);
}
spindle_data.rpm_programmed = spindle_data.rpm = rpm;
}
#else
static uint_fast16_t spindleGetPWM (spindle_ptrs_t *spindle, float rpm)
{
return spindle->context.pwm->compute_value(spindle->context.pwm, rpm, false);
}
#endif
// Start or stop spindle
static void spindleSetStateVariable (spindle_ptrs_t *spindle, spindle_state_t state, float rpm)
{
if(!(spindle->context.pwm->flags.cloned ? state.ccw : state.on)) {
spindle_off(spindle);
pwm_off(spindle);
} else {
#ifdef SPINDLE_DIRECTION_PIN
if(!spindle->context.pwm->flags.cloned)
spindle_dir(state.ccw);
#endif
if(rpm == 0.0f && spindle->context.pwm->flags.rpm_controlled)
spindle_off(spindle);
else {
spindle_on(spindle);
spindleSetSpeed(spindle, spindle->context.pwm->compute_value(spindle->context.pwm, rpm, false));
}
}
#ifdef SPINDLE_RPM_CONTROLLED
if (!state.on || rpm == 0.0f) {
spindleSetSpeed(spindle, spindle->context.pwm->off_value);
spindle_control.rpm = 0.0f;
spindle_control.pid_state = PIDState_Disabled;
pidf_reset(&spindle_control.pid);
spindle_control.pid.sample_rate_prev = 1.0f;
} else {
if(spindle_data.rpm_programmed == 0.0f) {
if(spindle_control.pid_enabled) {
pid_count = 0;
spindle_control.pid_state = PIDState_Pending;
}
}
#ifdef sPID_LOG
sys.pid_log.idx = 0;
#endif
spindleSetSpeed(spindle, spindle->context.pwm->compute_value(spindle->context.pwm, rpm + spindle_control.pid.error, spindle_control.pid.error != 0.0f));
}
#endif
#if SPINDLE_ENCODER_ENABLE
if(spindle->at_speed_tolerance > 0.0f) {
float tolerance = rpm * spindle->at_speed_tolerance / 100.0f;
spindle_data.rpm_low_limit = rpm - tolerance;
spindle_data.rpm_high_limit = rpm + tolerance;
}
spindle_data.state_programmed.on = state.on;
spindle_data.state_programmed.ccw = state.ccw;
spindle_data.rpm_programmed = spindle_data.rpm = rpm;
#endif
}
#endif // DRIVER_SPINDLE_ENABLE & SPINDLE_PWM
// Returns spindle state in a spindle_state_t variable
static spindle_state_t spindleGetState (spindle_ptrs_t *spindle)
{
spindle_state_t state = { settings.pwm_spindle.invert.mask };
// state.on = (SPINDLE_ENABLE_PORT->IN & SPINDLE_ENABLE_BIT) != 0;
state.on = BITBAND_PERI(SPINDLE_ENABLE_PORT->IN, SPINDLE_ENABLE_PIN);
state.ccw = BITBAND_PERI(SPINDLE_DIRECTION_PORT->IN, SPINDLE_DIRECTION_PIN);
state.value ^= settings.pwm_spindle.invert.mask;
#ifdef SPINDLE_PWM_PIN
state.on |= spindle->param->state.on;
#endif
#if SPINDLE_ENCODER_ENABLE
if(spindle && spindle->get_data) {
spindle_data_t *spindle_data = spindle->get_data(SpindleData_AtSpeed);
state.at_speed = spindle_data->state_programmed.at_speed;
state.encoder_error = spindle_data->error_count > 0;
}
#else
UNUSED(spindle);
#endif
return state;
}
#ifdef SPINDLE_RPM_CONTROLLED
inline static void spindle_rpm_pid (uint32_t tpp)
{
spindleLock = true;
spindle_control.rpm = spindle_calc_rpm(tpp);
float error = pidf(&spindle_control.pid, spindle_data.rpm_programmed, spindle_control.rpm, 1.0);
#ifdef sPID_LOG
if(sys.pid_log.idx < PID_LOG) {
sys.pid_log.target[sys.pid_log.idx] = error;
sys.pid_log.actual[sys.pid_log.idx] = rpm;
sys.pid_log.idx++;
}
#endif
SPINDLE_PWM_TIMER->CCR[2] = spindle_pwm.compute_value(&spindle_pwm, spindle_data.rpm_programmed + error, error != 0.0f);
spindleLock = false;
}
#endif
bool spindleConfig (spindle_ptrs_t *spindle)
{
if(spindle == NULL)
return false;
if(spindle_precompute_pwm_values(spindle, &spindle_pwm, &settings.pwm_spindle, 12000000UL / (settings.pwm_spindle.pwm_freq > 200.0f ? 2 : 16))) {
spindle->set_state = spindleSetStateVariable;
if(settings.pwm_spindle.pwm_freq > 200.0f)
SPINDLE_PWM_TIMER->CTL &= ~TIMER_A_CTL_ID__8;
else
SPINDLE_PWM_TIMER->CTL |= TIMER_A_CTL_ID__8;
SPINDLE_PWM_TIMER->CCR[0] = spindle_pwm.period;
SPINDLE_PWM_TIMER->CCTL[2] = settings.pwm_spindle.invert.pwm ? TIMER_A_CCTLN_OUT : 0; // Set PWM output according to invert setting and
SPINDLE_PWM_TIMER->CTL |= TIMER_A_CTL_CLR|TIMER_A_CTL_MC0|TIMER_A_CTL_MC1; // start PWM timer (with no pulse output)
spindle->set_state = spindleSetStateVariable;
} else {
if(spindle->param->state.on)
spindle->set_state(spindle, (spindle_state_t){0}, 0.0f);
spindle->set_state = spindleSetState;
}
spindle->cap.at_speed = spindle->cap.variable && settings.spindle.ppr > 0;
spindle_update_caps(spindle, spindle->cap.variable ? &spindle_pwm : NULL);
#ifdef SPINDLE_RPM_CONTROLLED
if((spindle_control.pid_enabled = spindle->get_data && (settings.spindle.pid.p_gain != 0.0) || pidf_config_changed(&spindle_control.pid, &settings.spindle.pid))) {
spindle->set_state((spindle_state_t){0}, 0.0f);
pidf_init(&spindle_control.pid, &settings.spindle.pid);
// spindle_encoder.pid.cfg.i_max_error = spindle_encoder.pid.cfg.i_max_error / settings->spindle.pid.i_gain; // Makes max value sensible?
} else
spindle_control.pid_state = PIDState_Disabled;
#endif
return true;
}
#endif // DRIVER_SPINDLE_ENABLE & SPINDLE_PWM
#if SPINDLE_ENCODER_ENABLE
static spindle_data_t *spindleGetData (spindle_data_request_t request)
{
bool stopped;
uint32_t pulse_length, rpm_timer_delta;
spindle_encoder_counter_t encoder;
while(spindle_encoder.spin_lock);
__disable_irq();
memcpy(&encoder, &spindle_encoder.counter, sizeof(spindle_encoder_counter_t));
pulse_length = spindle_encoder.timer.pulse_length / spindle_encoder.tics_per_irq;
rpm_timer_delta = spindle_encoder.timer.last_pulse - RPM_TIMER->VALUE; // NOTE: timer is counting down!
__enable_irq();
// If no (4) spindle pulses during last 250mS assume RPM is 0
if((stopped = ((pulse_length == 0) || (rpm_timer_delta > spindle_encoder.maximum_tt)))) {
spindle_data.rpm = 0.0f;
rpm_timer_delta = (RPM_COUNTER->R - (uint16_t)spindle_encoder.counter.last_count) * pulse_length;
}
switch(request) {
case SpindleData_Counters:
spindle_data.index_count = encoder.index_count;
spindle_data.pulse_count = encoder.pulse_count + (uint32_t)((uint16_t)RPM_COUNTER->R - (uint16_t)encoder.last_count);
spindle_data.error_count = spindle_encoder.error_count;
break;
case SpindleData_RPM:
if(!stopped)
#ifdef SPINDLE_RPM_CONTROLLED