forked from donovan6000/iMe
-
Notifications
You must be signed in to change notification settings - Fork 1
/
motors.cpp
executable file
·2207 lines (1642 loc) · 70.9 KB
/
motors.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
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
// DRV8834 motor driver http://www.ti.com/lit/ds/slvsb19d/slvsb19d.pdf
// 24BYJ-48 5V 1/64 ratio stepper motor used in 4 wire bipolar mode, so just ignore the common wire (usually red) if it has one. Connecting a new motor to the existing male connector can be done by connecting the following wires: pink to grey, yellow to black, red to nothing, blue to orange, and orange to blue. http://robocraft.ru/files/datasheet/28BYJ-48.pdf
// Header files
extern "C" {
#include <asf.h>
}
#include <math.h>
#include <string.h>
#include "common.h"
#include "eeprom.h"
#include "heater.h"
#include "motors.h"
// Definitions
#define SEGMENT_LENGTH 2.0
#define HOMING_FEED_RATE 1500.0
#define CALIBRATING_Z_FEED_RATE 17.0
#define INVALID_BED_ORIENTATION_VERSION UINT8_MAX
#define BED_ORIENTATION_VERSION 1
#define HOMING_ADDITIONAL_DISTANCE 8.0
// Bed dimensions
#define BED_CENTER_X 54.0
#define BED_CENTER_Y 50.0
#define BED_CENTER_X_DISTANCE_FROM_HOMING_CORNER 55.0
#define BED_CENTER_Y_DISTANCE_FROM_HOMING_CORNER 55.0
#define BED_CALIBRATION_POSITIONS_DISTANCE_FROM_CENTER 45.0
#define BED_LOW_MAX_X 106.0
#define BED_LOW_MIN_X -2.0
#define BED_LOW_MAX_Y 105.0
#define BED_LOW_MIN_Y -2.0
#define BED_LOW_MAX_Z 5.0
#define BED_LOW_MIN_Z 0.0
#define BED_MEDIUM_MAX_X 106.0
#define BED_MEDIUM_MIN_X -2.0
#define BED_MEDIUM_MAX_Y 105.0
#define BED_MEDIUM_MIN_Y -9.0
#define BED_MEDIUM_MAX_Z 73.5
#define BED_MEDIUM_MIN_Z BED_LOW_MAX_Z
#define BED_HIGH_MAX_X 97.0
#define BED_HIGH_MIN_X 7.0
#define BED_HIGH_MAX_Y 85.0
#define BED_HIGH_MIN_Y 9.0
#define BED_HIGH_MAX_Z 112.0
#define BED_HIGH_MIN_Z BED_MEDIUM_MAX_Z
// Motors settings
#define MICROSTEPS_PER_STEP 8
#define MOTORS_ENABLE_PIN IOPORT_CREATE_PIN(PORTB, 3)
#define MOTORS_STEP_CONTROL_PIN IOPORT_CREATE_PIN(PORTB, 2)
#define MOTORS_CURRENT_SENSE_RESISTANCE 0.1
#define MOTORS_CURRENT_TO_VOLTAGE_SCALAR (5.0 * MOTORS_CURRENT_SENSE_RESISTANCE)
#define MOTORS_SAVE_TIMER_PERIOD MOTORS_VREF_TIMER_PERIOD
#define MOTORS_SAVE_VALUE_MILLISECONDS 200
#define MOTORS_STEP_TIMER TCC0
#define MOTORS_STEP_TIMER_PERIOD 1024
// Motor X settings
#define MOTOR_X_DIRECTION_PIN IOPORT_CREATE_PIN(PORTC, 2)
#define MOTOR_X_VREF_PIN IOPORT_CREATE_PIN(PORTD, 1)
#define MOTOR_X_STEP_PIN IOPORT_CREATE_PIN(PORTC, 5)
#define MOTOR_X_VREF_CHANNEL TC_CCB
#define MOTOR_X_VREF_CHANNEL_CAPTURE_COMPARE TC_CCBEN
#define MOTOR_X_CURRENT_IDLE 0.692018779
#define MOTOR_X_CURRENT_ACTIVE 0.723004695
// Motor Y settings
#define MOTOR_Y_DIRECTION_PIN IOPORT_CREATE_PIN(PORTD, 5)
#define MOTOR_Y_VREF_PIN IOPORT_CREATE_PIN(PORTD, 3)
#define MOTOR_Y_STEP_PIN IOPORT_CREATE_PIN(PORTC, 7)
#define MOTOR_Y_VREF_CHANNEL TC_CCD
#define MOTOR_Y_VREF_CHANNEL_CAPTURE_COMPARE TC_CCDEN
#define MOTOR_Y_CURRENT_IDLE 0.692018779
#define MOTOR_Y_CURRENT_ACTIVE 0.82629108
// Motor Z settings
#define MOTOR_Z_DIRECTION_PIN IOPORT_CREATE_PIN(PORTD, 4)
#define MOTOR_Z_VREF_PIN IOPORT_CREATE_PIN(PORTD, 2)
#define MOTOR_Z_STEP_PIN IOPORT_CREATE_PIN(PORTC, 6)
#define MOTOR_Z_VREF_CHANNEL TC_CCC
#define MOTOR_Z_VREF_CHANNEL_CAPTURE_COMPARE TC_CCCEN
#define MOTOR_Z_CURRENT_IDLE 0.196244131
#define MOTOR_Z_CURRENT_ACTIVE 0.650704225
// Motor E settings
#define MOTOR_E_DIRECTION_PIN IOPORT_CREATE_PIN(PORTC, 3)
#define MOTOR_E_VREF_PIN IOPORT_CREATE_PIN(PORTD, 0)
#define MOTOR_E_STEP_PIN IOPORT_CREATE_PIN(PORTC, 4)
#define MOTOR_E_CURRENT_SENSE_ADC ADC_MODULE
#define MOTOR_E_CURRENT_SENSE_PIN IOPORT_CREATE_PIN(PORTA, 7)
#define MOTOR_E_CURRENT_SENSE_ADC_FREQUENCY 200000
#define MOTOR_E_CURRENT_SENSE_ADC_SAMPLE_SIZE 50
#define MOTOR_E_CURRENT_SENSE_ADC_CHANNEL ADC_CH0
#define MOTOR_E_CURRENT_SENSE_ADC_PIN ADCCH_POS_PIN7
#define MOTOR_E_VREF_CHANNEL TC_CCA
#define MOTOR_E_VREF_CHANNEL_CAPTURE_COMPARE TC_CCAEN
#define MOTOR_E_CURRENT_IDLE 0.299530516
// Pin states
#define MOTORS_ON IOPORT_PIN_LEVEL_LOW
#define MOTORS_OFF IOPORT_PIN_LEVEL_HIGH
#define DIRECTION_LEFT IOPORT_PIN_LEVEL_HIGH
#define DIRECTION_RIGHT IOPORT_PIN_LEVEL_LOW
#define DIRECTION_BACKWARD IOPORT_PIN_LEVEL_HIGH
#define DIRECTION_FORWARD IOPORT_PIN_LEVEL_LOW
#define DIRECTION_UP IOPORT_PIN_LEVEL_HIGH
#define DIRECTION_DOWN IOPORT_PIN_LEVEL_LOW
#define DIRECTION_EXTRUDE IOPORT_PIN_LEVEL_LOW
#define DIRECTION_RETRACT IOPORT_PIN_LEVEL_HIGH
// X, Y, and Z states
#define INVALID 0x00
#define VALID 0x01
// Global variables
Motors *self;
uint32_t motorsDelaySkips[NUMBER_OF_MOTORS];
uint32_t motorsDelaySkipsCounter[NUMBER_OF_MOTORS];
uint32_t motorsStepDelay[NUMBER_OF_MOTORS];
uint32_t motorsStepDelayCounter[NUMBER_OF_MOTORS];
uint32_t motorsNumberOfSteps[NUMBER_OF_MOTORS];
float motorsNumberOfRemainingSteps[NUMBER_OF_MOTORS];
bool motorsIsMoving[NUMBER_OF_MOTORS];
// Function prototypes
/*
Name: Motors step action
Purpose: Performs one step for the specified motor
*/
void motorsStepAction(Axes motor) noexcept;
/*
Name: Update motors' step timer
Purpose: Performs actions for all motors that are still moving
*/
void updateMotorsStepTimer() noexcept;
// Check if bed leveling is enabled
#if ENABLE_BED_LEVELING_COMPENSATION == true
/*
Name: Calculate plance normal vector
Purpose: Returns the normal vector for the plane whos corners are each specified value
*/
inline Vector calculatePlaneNormalVector(const Vector &v1, const Vector &v2, const Vector &v3) noexcept;
/*
Name: Generate plane equation
Purpose: Returns a plane whos corners are each specified value
*/
Vector generatePlaneEquation(const Vector &v1, const Vector &v2, const Vector &v3) noexcept;
/*
Name: Get Z from XY and plane
Purpose: Returns a plane's Z value at the provided point
*/
float getZFromXYAndPlane(const Vector &point, const Vector &planeABC) noexcept;
/*
Name: Sign
Purpose: Returns the direction of the first point in relation to the other points
*/
float sign(const Vector &p1, const Vector &p2, const Vector &p3) noexcept;
/*
Name: Is point in triangle
Purpose: Returns if a specified point is in the triangle whos corners are each specified value
*/
bool isPointInTriangle(const Vector &pt, const Vector &v1, const Vector &v2, const Vector &v3) noexcept;
#endif
// Supporting function implementation
void motorsStepAction(Axes motor) noexcept {
// The motorsDelaySkips and motorsStepDelay are used to delay the motor's movements to make sure that all motors end at the same time given the feed rate of the movement and all the motor's speed limits
// totalCpuCycles[motor] = ceil(motorsNumberOfSteps[motor] * motorsStepDelay[motor] * (1 + (motorsDelaySkips[motor] ? 1 / motorsDelaySkips[motor] : 0)) - (motorsDelaySkips[motor] ? 1 : 0)) * MOTORS_STEP_TIMER_PERIOD;
// Check if time to skip a motor delay
if(motorsDelaySkips[motor] && motorsDelaySkipsCounter[motor]++ >= motorsDelaySkips[motor])
// Clear motor skip delay counter
motorsDelaySkipsCounter[motor] = 0;
// Otherwise check if time to increment motor step
else if(++motorsStepDelayCounter[motor] >= motorsStepDelay[motor]) {
// Check if done moving motor
if(!--motorsNumberOfSteps[motor])
// Set that motor isn't moving
motorsIsMoving[motor] = false;
// Set motor step pin
switch(motor) {
case X:
ioport_set_pin_level(MOTOR_X_STEP_PIN, IOPORT_PIN_LEVEL_HIGH);
break;
case Y:
ioport_set_pin_level(MOTOR_Y_STEP_PIN, IOPORT_PIN_LEVEL_HIGH);
break;
case Z:
ioport_set_pin_level(MOTOR_Z_STEP_PIN, IOPORT_PIN_LEVEL_HIGH);
break;
case E:
default:
ioport_set_pin_level(MOTOR_E_STEP_PIN, IOPORT_PIN_LEVEL_HIGH);
}
// Clear motor step counter
motorsStepDelayCounter[motor] = 0;
}
}
void updateMotorsStepTimer() noexcept {
// Clear motor X, Y, Z, and E step pins
ioport_set_pin_level(MOTOR_X_STEP_PIN, IOPORT_PIN_LEVEL_LOW);
ioport_set_pin_level(MOTOR_Y_STEP_PIN, IOPORT_PIN_LEVEL_LOW);
ioport_set_pin_level(MOTOR_Z_STEP_PIN, IOPORT_PIN_LEVEL_LOW);
ioport_set_pin_level(MOTOR_E_STEP_PIN, IOPORT_PIN_LEVEL_LOW);
// Go through all motors
for(uint8_t i = 0; i < NUMBER_OF_MOTORS; ++i)
// Check if motor is moving
if(motorsIsMoving[i])
// Perform motor step action
motorsStepAction(static_cast<Axes>(i));
}
// Check if bed leveling is enabled
#if ENABLE_BED_LEVELING_COMPENSATION == true
Vector calculatePlaneNormalVector(const Vector &v1, const Vector &v2, const Vector &v3) noexcept {
// Initialize variables
Vector vector1 = v2 - v1;
Vector vector2 = v3 - v1;
// Return normal vector
return {vector1[1] * vector2[2] - vector2[1] * vector1[2], vector1[2] * vector2[0] - vector2[2] * vector1[0], vector1[0] * vector2[1] - vector2[0] * vector1[1], 0};
}
Vector generatePlaneEquation(const Vector &v1, const Vector &v2, const Vector &v3) noexcept {
// Initialize variables
Vector vector = calculatePlaneNormalVector(v1, v2, v3);
// Return plane equation
return {vector[0], vector[1], vector[2], -(vector[0] * v1[0] + vector[1] * v1[1] + vector[2] * v1[2])};
}
float getZFromXYAndPlane(const Vector &point, const Vector &planeABC) noexcept {
// Return Z
return planeABC[2] ? (planeABC[0] * point.x + planeABC[1] * point.y + planeABC[3]) / -planeABC[2] : 0;
}
float sign(const Vector &p1, const Vector &p2, const Vector &p3) noexcept {
// Return sign
return (p1.x - p3.x) * (p2.y - p3.y) - (p2.x - p3.x) * (p1.y - p3.y);
}
bool isPointInTriangle(const Vector &pt, const Vector &v1, const Vector &v2, const Vector &v3) noexcept {
// Initialize variables
Vector vector1 = v1 - v2 + v1 - v3;
vector1.normalize();
Vector vector2 = v1 + vector1 * 0.01;
vector1 = v2 - v1 + v2 - v3;
vector1.normalize();
Vector vector3 = v2 + vector1 * 0.01;
vector1 = v3 - v1 + v3 - v2;
vector1.normalize();
Vector vector4 = v3 + vector1 * 0.01;
// Return if inside triangle
bool flag = sign(pt, vector2, vector3) < 0;
bool flag2 = sign(pt, vector3, vector4) < 0;
bool flag3 = sign(pt, vector4, vector2) < 0;
return flag == flag2 && flag2 == flag3;
}
#endif
bool Motors::areMotorsMoving() noexcept {
// Go through all motors
for(uint8_t i = 0; i < NUMBER_OF_MOTORS; ++i)
// Check if motor is moving
if(motorsIsMoving[i])
// Return true
return true;
// Return false
return false;
}
void Motors::startMotorsStepTimer() noexcept {
// Turn on motors
turnOn();
// Restart motors step timer
tc_restart(&MOTORS_STEP_TIMER);
tc_write_clock_source(&MOTORS_STEP_TIMER, TC_CLKSEL_DIV1_gc);
}
void Motors::stopMotorsStepTimer() noexcept {
// Stop motors step timer
tc_write_clock_source(&MOTORS_STEP_TIMER, TC_CLKSEL_OFF_gc);
// Set that motors aren't moving
memset(motorsIsMoving, false, sizeof(motorsIsMoving));
// Update motors step timer
updateMotorsStepTimer();
}
// Check if bed leveling is enabled
#if ENABLE_BED_LEVELING_COMPENSATION == true
float Motors::getHeightAdjustmentRequired(float x, float y) noexcept {
// Initialize variables
Vector point;
point.initialize(x, y);
// Return height adjustment
if(x <= frontLeftVector.x && y >= backRightVector.y)
return (getZFromXYAndPlane(point, backPlane) + getZFromXYAndPlane(point, leftPlane)) / 2;
else if(x <= frontLeftVector.x && y <= frontLeftVector.y)
return (getZFromXYAndPlane(point, frontPlane) + getZFromXYAndPlane(point, leftPlane)) / 2;
else if(x >= frontRightVector.x && y <= frontLeftVector.y)
return (getZFromXYAndPlane(point, frontPlane) + getZFromXYAndPlane(point, rightPlane)) / 2;
else if(x >= frontRightVector.x && y >= backRightVector.y)
return (getZFromXYAndPlane(point, backPlane) + getZFromXYAndPlane(point, rightPlane)) / 2;
else if(x <= frontLeftVector.x)
return getZFromXYAndPlane(point, leftPlane);
else if(x >= frontRightVector.x)
return getZFromXYAndPlane(point, rightPlane);
else if(y >= backRightVector.y)
return getZFromXYAndPlane(point, backPlane);
else if(y <= frontLeftVector.y)
return getZFromXYAndPlane(point, frontPlane);
else if(isPointInTriangle(point, centerVector, frontLeftVector, backLeftVector))
return getZFromXYAndPlane(point, leftPlane);
else if(isPointInTriangle(point, centerVector, frontRightVector, backRightVector))
return getZFromXYAndPlane(point, rightPlane);
else if(isPointInTriangle(point, centerVector, backLeftVector, backRightVector))
return getZFromXYAndPlane(point, backPlane);
return getZFromXYAndPlane(point, frontPlane);
}
#endif
// Check if skew compensation is enabled
#if ENABLE_SKEW_COMPENSATION == true
float Motors::getSkewAdjustmentRequired(Axes axis, float height) noexcept {
// Return skew adjustment
return BED_HIGH_MAX_Z - externalBedHeight - BED_LOW_MIN_Z ? height / (BED_HIGH_MAX_Z - externalBedHeight - BED_LOW_MIN_Z) * -(axis == X ? skewX : skewY) : 0;
}
#endif
void Motors::initialize() noexcept {
// Restore state
restoreState();
// Set modes
mode = extruderMode = ABSOLUTE;
// Set units
units = MILLIMETERS;
// Set initial values
currentValues[F] = EEPROM_SPEED_LIMIT_X_MAX;
// Configure motors enable
ioport_set_pin_dir(MOTORS_ENABLE_PIN, IOPORT_DIR_OUTPUT);
// Turn off
turnOff();
// Set 8 microsteps/step
#if MICROSTEPS_PER_STEP == 8
// Configure motor's step control
ioport_set_pin_dir(MOTORS_STEP_CONTROL_PIN, IOPORT_DIR_OUTPUT);
ioport_set_pin_level(MOTORS_STEP_CONTROL_PIN, IOPORT_PIN_LEVEL_LOW);
// Otherwise set 16 microsteps/step
#elif MICROSTEPS_PER_STEP == 16
// Configure motor's step control
ioport_set_pin_dir(MOTORS_STEP_CONTROL_PIN, IOPORT_DIR_OUTPUT);
ioport_set_pin_level(MOTORS_STEP_CONTROL_PIN, IOPORT_PIN_LEVEL_HIGH);
// Otherwise set 32 microsteps/step
#else
// Configure motor's step control
ioport_set_pin_dir(MOTORS_STEP_CONTROL_PIN, IOPORT_DIR_INPUT);
ioport_set_pin_mode(MOTORS_STEP_CONTROL_PIN, IOPORT_MODE_TOTEM);
#endif
// Configure motor X Vref, direction, and step
ioport_set_pin_dir(MOTOR_X_VREF_PIN, IOPORT_DIR_OUTPUT);
ioport_set_pin_dir(MOTOR_X_DIRECTION_PIN, IOPORT_DIR_OUTPUT);
ioport_set_pin_level(MOTOR_X_DIRECTION_PIN, currentMotorDirections[X]);
ioport_set_pin_dir(MOTOR_X_STEP_PIN, IOPORT_DIR_OUTPUT);
// Configure motor Y Vref, direction, and step
ioport_set_pin_dir(MOTOR_Y_VREF_PIN, IOPORT_DIR_OUTPUT);
ioport_set_pin_dir(MOTOR_Y_DIRECTION_PIN, IOPORT_DIR_OUTPUT);
ioport_set_pin_level(MOTOR_Y_DIRECTION_PIN, currentMotorDirections[Y]);
ioport_set_pin_dir(MOTOR_Y_STEP_PIN, IOPORT_DIR_OUTPUT);
// Configure motor Z VREF, direction, and step
ioport_set_pin_dir(MOTOR_Z_VREF_PIN, IOPORT_DIR_OUTPUT);
ioport_set_pin_dir(MOTOR_Z_DIRECTION_PIN, IOPORT_DIR_OUTPUT);
ioport_set_pin_dir(MOTOR_Z_STEP_PIN, IOPORT_DIR_OUTPUT);
// Configure motor E VREF, direction, step, and current sense
ioport_set_pin_dir(MOTOR_E_VREF_PIN, IOPORT_DIR_OUTPUT);
ioport_set_pin_dir(MOTOR_E_DIRECTION_PIN, IOPORT_DIR_OUTPUT);
ioport_set_pin_dir(MOTOR_E_STEP_PIN, IOPORT_DIR_OUTPUT);
ioport_set_pin_dir(MOTOR_E_CURRENT_SENSE_PIN, IOPORT_DIR_INPUT);
ioport_set_pin_mode(MOTOR_E_CURRENT_SENSE_PIN, IOPORT_MODE_PULLDOWN);
// Configure motors Vref timer
tc_enable(&MOTORS_VREF_TIMER);
tc_set_wgm(&MOTORS_VREF_TIMER, TC_WG_SS);
tc_write_period(&MOTORS_VREF_TIMER, MOTORS_VREF_TIMER_PERIOD);
tc_write_cc(&MOTORS_VREF_TIMER, MOTOR_X_VREF_CHANNEL, round(MOTOR_X_CURRENT_IDLE * MOTORS_CURRENT_TO_VOLTAGE_SCALAR / MICROCONTROLLER_VOLTAGE * MOTORS_VREF_TIMER_PERIOD));
tc_write_cc(&MOTORS_VREF_TIMER, MOTOR_Y_VREF_CHANNEL, round(MOTOR_Y_CURRENT_IDLE * MOTORS_CURRENT_TO_VOLTAGE_SCALAR / MICROCONTROLLER_VOLTAGE * MOTORS_VREF_TIMER_PERIOD));
tc_write_cc(&MOTORS_VREF_TIMER, MOTOR_Z_VREF_CHANNEL, round(MOTOR_Z_CURRENT_IDLE * MOTORS_CURRENT_TO_VOLTAGE_SCALAR / MICROCONTROLLER_VOLTAGE * MOTORS_VREF_TIMER_PERIOD));
tc_write_cc(&MOTORS_VREF_TIMER, MOTOR_E_VREF_CHANNEL, round(MOTOR_E_CURRENT_IDLE * MOTORS_CURRENT_TO_VOLTAGE_SCALAR / MICROCONTROLLER_VOLTAGE * MOTORS_VREF_TIMER_PERIOD));
tc_enable_cc_channels(&MOTORS_VREF_TIMER, static_cast<tc_cc_channel_mask_enable_t>(MOTOR_X_VREF_CHANNEL_CAPTURE_COMPARE | MOTOR_Y_VREF_CHANNEL_CAPTURE_COMPARE | MOTOR_Z_VREF_CHANNEL_CAPTURE_COMPARE | MOTOR_E_VREF_CHANNEL_CAPTURE_COMPARE));
tc_write_clock_source(&MOTORS_VREF_TIMER, TC_CLKSEL_DIV1_gc);
// Configure motors step timer
tc_enable(&MOTORS_STEP_TIMER);
tc_set_wgm(&MOTORS_STEP_TIMER, TC_WG_NORMAL);
tc_write_period(&MOTORS_STEP_TIMER, MOTORS_STEP_TIMER_PERIOD);
tc_set_overflow_interrupt_level(&MOTORS_STEP_TIMER, TC_INT_LVL_MED);
// Reset
reset();
// Motors step timer overflow callback
tc_set_overflow_interrupt_callback(&MOTORS_STEP_TIMER, updateMotorsStepTimer);
// Check if regulating extruder current
#if REGULATE_EXTRUDER_CURRENT == true
// Set ADC controller to use unsigned, 12-bit, Vref refrence, and manual trigger
adc_read_configuration(&MOTOR_E_CURRENT_SENSE_ADC, ¤tSenseAdcController);
adc_set_conversion_parameters(¤tSenseAdcController, ADC_SIGN_OFF, ADC_RES_12, ADC_REF_AREFA);
adc_set_conversion_trigger(¤tSenseAdcController, ADC_TRIG_MANUAL, ADC_NR_OF_CHANNELS, 0);
adc_set_clock_rate(¤tSenseAdcController, MOTOR_E_CURRENT_SENSE_ADC_FREQUENCY);
// Set ADC channel to use motor E current sense pin as single ended input with no gain
adcch_read_configuration(&MOTOR_E_CURRENT_SENSE_ADC, MOTOR_E_CURRENT_SENSE_ADC_CHANNEL, ¤tSenseAdcChannel);
adcch_set_input(¤tSenseAdcChannel, MOTOR_E_CURRENT_SENSE_ADC_PIN, ADCCH_NEG_NONE, 1);
#endif
// Initialize accelerometer
accelerometer.initialize();
// Check if bed leveling is enabled
#if ENABLE_BED_LEVELING_COMPENSATION == true
// Set vectors
backRightVector.initialize(BED_CENTER_X + BED_CALIBRATION_POSITIONS_DISTANCE_FROM_CENTER, BED_CENTER_Y + BED_CALIBRATION_POSITIONS_DISTANCE_FROM_CENTER);
backLeftVector.initialize(BED_CENTER_X - BED_CALIBRATION_POSITIONS_DISTANCE_FROM_CENTER, BED_CENTER_Y + BED_CALIBRATION_POSITIONS_DISTANCE_FROM_CENTER);
frontLeftVector.initialize(BED_CENTER_X - BED_CALIBRATION_POSITIONS_DISTANCE_FROM_CENTER, BED_CENTER_Y - BED_CALIBRATION_POSITIONS_DISTANCE_FROM_CENTER);
frontRightVector.initialize(BED_CENTER_X + BED_CALIBRATION_POSITIONS_DISTANCE_FROM_CENTER, BED_CENTER_Y - BED_CALIBRATION_POSITIONS_DISTANCE_FROM_CENTER);
centerVector.initialize(BED_CENTER_X, BED_CENTER_Y);
#endif
// Update bed changes
updateBedChanges(false);
// Configure motors save interrupt
self = this;
tc_set_overflow_interrupt_callback(&MOTORS_SAVE_TIMER, []() noexcept -> void {
// Initialize variables
static uint16_t motorsSaveTimerCounter;
static Axes currentSaveMotor = Z;
static AxesParameter currentSaveParameter = VALUE;
// Check if enough time to save a value has passed
if(++motorsSaveTimerCounter >= sysclk_get_cpu_hz() / MOTORS_SAVE_TIMER_PERIOD * MOTORS_SAVE_VALUE_MILLISECONDS / 1000) {
// Reset motors save timer counter
motorsSaveTimerCounter = 0;
// Check if all parameters for the current motor have been saved
if(currentSaveParameter == VALUE) {
// Reset current save parameter
currentSaveParameter = DIRECTION;
// Set current save motor to next motor
currentSaveMotor = currentSaveMotor == Z ? X : static_cast<Axes>(currentSaveMotor + 1);
}
// Otherwise
else
// Set current save parameter to next parameter
currentSaveParameter = static_cast<AxesParameter>(currentSaveParameter + 1);
// Wait until non-volatile memory controller isn't busy
nvm_wait_until_ready();
// Save non-volatile memory controller's state
NVM_t savedNvmState;
memcpy(&savedNvmState, &NVM, sizeof(NVM_t));
// Save current motor's state
self->saveState(currentSaveMotor, currentSaveParameter);
// Wait until non-volatile memory controller isn't busy
nvm_wait_until_ready();
// Restore non-volatile memory controller's state
memcpy(&NVM, &savedNvmState, sizeof(NVM_t));
}
});
tc_set_overflow_interrupt_level(&MOTORS_SAVE_TIMER, TC_INT_LVL_LO);
}
void Motors::turnOn() noexcept {
// Turn on motors
ioport_set_pin_level(MOTORS_ENABLE_PIN, MOTORS_ON);
}
void Motors::turnOff() noexcept {
// Turn off motors
ioport_set_pin_level(MOTORS_ENABLE_PIN, MOTORS_OFF);
}
bool Motors::move(const Gcode &gcode, uint8_t tasks) noexcept {
// Initialize variables
bool validValues[3];
// Check if performing a task
if(tasks) {
// Set motors start values
memcpy(startValues, currentValues, sizeof(startValues));
// Save motors validities
memcpy(validValues, currentStateOfValues, sizeof(validValues));
}
// Check if G-code has an F parameter
if(gcode.commandParameters & PARAMETER_F_OFFSET) {
// Set F value
currentValues[F] = gcode.valueF;
// Check if units are inches and movement is from a received command
if(units == INCHES && tasks & HANDLE_RECEIVED_COMMAND_TASK)
// Convert F value to millimeters
currentValues[F] *= INCHES_TO_MILLIMETERS_SCALAR;
}
// Save motors current values
float newValues[NUMBER_OF_MOTORS];
memcpy(newValues, currentValues, sizeof(newValues));
// Go through all motors
for(int8_t i = NUMBER_OF_MOTORS - 1; i >= 0; --i) {
// Get parameter offset and parameter value
gcodeParameterOffset currentParameterOffset;
float currentValue;
switch(i) {
case X:
currentParameterOffset = PARAMETER_X_OFFSET;
currentValue = gcode.valueX;
break;
case Y:
currentParameterOffset = PARAMETER_Y_OFFSET;
currentValue = gcode.valueY;
break;
case Z:
currentParameterOffset = PARAMETER_Z_OFFSET;
currentValue = gcode.valueZ;
break;
case E:
default:
currentParameterOffset = PARAMETER_E_OFFSET;
currentValue = gcode.valueE;
}
// Check if G-code has parameter
if(gcode.commandParameters & currentParameterOffset) {
// Check if movement is from a received command and units are inches
if(tasks & HANDLE_RECEIVED_COMMAND_TASK && units == INCHES)
// Convert value to millimeters
currentValue *= INCHES_TO_MILLIMETERS_SCALAR;
// Check if movement is relative
if(((i == X || i == Y || i == Z) && mode == RELATIVE) || (i == E && extruderMode == RELATIVE))
// Add current value to value
currentValue += currentValues[i];
// Save new value
newValues[i] = currentValue;
}
}
// Check if enforcing boundaries
#if ENABLE_BOUNDARY_ENFORCING == true
// Check if movement is from a received command
if(tasks & HANDLE_RECEIVED_COMMAND_TASK)
// Go through all tiers
for(Tiers currentTier = LOW_TIER;; currentTier = static_cast<Tiers>(currentTier + 1)) {
// Check if bed leveling or skew compensation is enabled
#if ENABLE_BED_LEVELING_COMPENSATION == true || ENABLE_SKEW_COMPENSATION == true
// Get minimum and maximum X and Y values based on current tier
float minValues[2], maxValues[2];
switch(currentTier) {
case LOW_TIER:
minValues[X] = BED_LOW_MIN_X;
minValues[Y] = BED_LOW_MIN_Y;
maxValues[X] = BED_LOW_MAX_X;
maxValues[Y] = BED_LOW_MAX_Y;
break;
case MEDIUM_TIER:
minValues[X] = BED_MEDIUM_MIN_X;
minValues[Y] = BED_MEDIUM_MIN_Y;
maxValues[X] = BED_MEDIUM_MAX_X;
maxValues[Y] = BED_MEDIUM_MAX_Y;
break;
case HIGH_TIER:
default:
minValues[X] = BED_HIGH_MIN_X;
minValues[Y] = BED_HIGH_MIN_Y;
maxValues[X] = BED_HIGH_MAX_X;
maxValues[Y] = BED_HIGH_MAX_Y;
}
#endif
// Check if bed leveling is enabled
#if ENABLE_BED_LEVELING_COMPENSATION == true
// Set potential X and Y values based on boundaries
float potentialValues[] = {
getValueInRange(newValues[X], minValues[X], maxValues[X]),
getValueInRange(newValues[Y], minValues[Y], maxValues[Y])
};
// Set potential Z based on height adjustment change
float potentialZ = newValues[Z] + getHeightAdjustmentRequired(potentialValues[X], potentialValues[Y]);
// Otherwise
#else
// Set potential Z based on height adjustment change
float potentialZ = newValues[Z];
#endif
// Check if resulting tier wasn't higher
if(currentTier >= getTierAtHeight(potentialZ)) {
// Check if skew compensation is enabled
#if ENABLE_SKEW_COMPENSATION == true
// Apply limited X and Y values with skewed boundaries
newValues[X] = getValueInRange(newValues[X], minValues[X] - getSkewAdjustmentRequired(X, potentialZ), maxValues[X] - getSkewAdjustmentRequired(X, potentialZ));
newValues[Y] = getValueInRange(newValues[Y], minValues[Y] - getSkewAdjustmentRequired(Y, potentialZ), maxValues[Y] - getSkewAdjustmentRequired(Y, potentialZ));
#endif
// Break
break;
}
}
#endif
// Initialize variables
float movementsHighestNumberOfCycles = 0;
BacklashDirection backlashDirections[] = {
NONE,
NONE
};
// Go through all motors
for(int8_t i = NUMBER_OF_MOTORS - 1; i >= 0; --i) {
// Check if motor moves
float distanceTraveled = fabs(newValues[i] - currentValues[i]);
if(distanceTraveled) {
// Set lower new value
bool lowerNewValue = newValues[i] < currentValues[i];
// Set current motor's settings
bool directionChange;
float stepsPerMm;
float speedLimit;
float maxFeedRate;
float minFeedRate;
switch(i) {
case X:
// Set direction change and steps/mm
directionChange = ioport_get_pin_output_level(MOTOR_X_DIRECTION_PIN) != (lowerNewValue ? DIRECTION_LEFT : DIRECTION_RIGHT);
nvm_eeprom_read_buffer(EEPROM_X_MOTOR_STEPS_PER_MM_OFFSET, &stepsPerMm, EEPROM_X_MOTOR_STEPS_PER_MM_LENGTH);
// Set direction, speed limit, and min/max feed rates if performing a movement
if(!tasks) {
ioport_set_pin_level(MOTOR_X_DIRECTION_PIN, lowerNewValue ? DIRECTION_LEFT : DIRECTION_RIGHT);
nvm_eeprom_read_buffer(EEPROM_SPEED_LIMIT_X_OFFSET, &speedLimit, EEPROM_SPEED_LIMIT_X_LENGTH);
maxFeedRate = EEPROM_SPEED_LIMIT_X_MAX;
minFeedRate = EEPROM_SPEED_LIMIT_X_MIN;
}
break;
case Y:
// Set direction change and steps/mm
directionChange = ioport_get_pin_output_level(MOTOR_Y_DIRECTION_PIN) != (lowerNewValue ? DIRECTION_FORWARD : DIRECTION_BACKWARD);
nvm_eeprom_read_buffer(EEPROM_Y_MOTOR_STEPS_PER_MM_OFFSET, &stepsPerMm, EEPROM_Y_MOTOR_STEPS_PER_MM_LENGTH);
// Set direction, speed limit, and min/max feed rates if performing a movement
if(!tasks) {
ioport_set_pin_level(MOTOR_Y_DIRECTION_PIN, lowerNewValue ? DIRECTION_FORWARD : DIRECTION_BACKWARD);
nvm_eeprom_read_buffer(EEPROM_SPEED_LIMIT_Y_OFFSET, &speedLimit, EEPROM_SPEED_LIMIT_Y_LENGTH);
maxFeedRate = EEPROM_SPEED_LIMIT_Y_MAX;
minFeedRate = EEPROM_SPEED_LIMIT_Y_MIN;
}
break;
case Z:
// Set direction change and steps/mm
directionChange = ioport_get_pin_output_level(MOTOR_Z_DIRECTION_PIN) != (lowerNewValue ? DIRECTION_DOWN : DIRECTION_UP);
nvm_eeprom_read_buffer(EEPROM_Z_MOTOR_STEPS_PER_MM_OFFSET, &stepsPerMm, EEPROM_Z_MOTOR_STEPS_PER_MM_LENGTH);
// Set direction, speed limit, and min/max feed rates if performing a movement
if(!tasks) {
ioport_set_pin_level(MOTOR_Z_DIRECTION_PIN, lowerNewValue ? DIRECTION_DOWN : DIRECTION_UP);
nvm_eeprom_read_buffer(EEPROM_SPEED_LIMIT_Z_OFFSET, &speedLimit, EEPROM_SPEED_LIMIT_Z_LENGTH);
maxFeedRate = EEPROM_SPEED_LIMIT_Z_MAX;
minFeedRate = EEPROM_SPEED_LIMIT_Z_MIN;
}
break;
case E:
default:
// Set direction change and steps/mm
directionChange = ioport_get_pin_output_level(MOTOR_E_DIRECTION_PIN) != (lowerNewValue ? DIRECTION_RETRACT : DIRECTION_EXTRUDE);
nvm_eeprom_read_buffer(EEPROM_E_MOTOR_STEPS_PER_MM_OFFSET, &stepsPerMm, EEPROM_E_MOTOR_STEPS_PER_MM_LENGTH);
// Set direction, speed limit, and min/max feed rates if performing a movement
if(!tasks) {
if(lowerNewValue) {
ioport_set_pin_level(MOTOR_E_DIRECTION_PIN, DIRECTION_RETRACT);
nvm_eeprom_read_buffer(EEPROM_SPEED_LIMIT_E_NEGATIVE_OFFSET, &speedLimit, EEPROM_SPEED_LIMIT_E_NEGATIVE_LENGTH);
maxFeedRate = EEPROM_SPEED_LIMIT_E_NEGATIVE_MAX;
minFeedRate = EEPROM_SPEED_LIMIT_E_NEGATIVE_MIN;
}
else {
ioport_set_pin_level(MOTOR_E_DIRECTION_PIN, DIRECTION_EXTRUDE);
nvm_eeprom_read_buffer(EEPROM_SPEED_LIMIT_E_POSITIVE_OFFSET, &speedLimit, EEPROM_SPEED_LIMIT_E_POSITIVE_LENGTH);
maxFeedRate = EEPROM_SPEED_LIMIT_E_POSITIVE_MAX;
minFeedRate = EEPROM_SPEED_LIMIT_E_POSITIVE_MIN;
}
}
}
// Get total number of steps
float totalNumberOfSteps = distanceTraveled * stepsPerMm * MICROSTEPS_PER_STEP + (directionChange ? -motorsNumberOfRemainingSteps[i] : motorsNumberOfRemainingSteps[i]);
// Update number of remaining steps if performing a movement
if(!tasks)
motorsNumberOfRemainingSteps[i] = totalNumberOfSteps;
// Check if moving at least one step in the current direction
if(totalNumberOfSteps >= 1) {
// Check if performing a movement
if(!tasks) {
// Set that motor moves
motorsIsMoving[i] = true;
// Set number of steps
motorsNumberOfSteps[i] = totalNumberOfSteps;
// Update number of remaining steps
motorsNumberOfRemainingSteps[i] -= motorsNumberOfSteps[i];
// Set motor feedrate
float motorFeedRate = min(currentValues[F], speedLimit);
// Enforce min/max feed rates
motorFeedRate = getValueInRange(motorFeedRate, minFeedRate, maxFeedRate);
// Set the movement's highest number of cycles
movementsHighestNumberOfCycles = max(getMovementsNumberOfCycles(static_cast<Axes>(i), stepsPerMm, motorFeedRate), movementsHighestNumberOfCycles);
}
// Otherwise
else {
// Check if movement is too big
if(totalNumberOfSteps > UINT32_MAX) {
// Disable saving motors state
tc_set_overflow_interrupt_level(&MOTORS_SAVE_TIMER, TC_INT_LVL_OFF);
// Restore motors start values
memcpy(currentValues, startValues, sizeof(startValues));
// Enable saving motors state
tc_set_overflow_interrupt_level(&MOTORS_SAVE_TIMER, TC_INT_LVL_LO);
// Restore motors validities
memcpy(currentStateOfValues, validValues, sizeof(validValues));
// Return false
return false;
}
// Check if current motor's validity gets saved
if(i == X || i == Y || i == Z) {
// Check if X or Y direction changed
if((i == X || i == Y) && currentMotorDirections[i] != (lowerNewValue ? (i == X ? DIRECTION_LEFT : DIRECTION_FORWARD) : (i == X ? DIRECTION_RIGHT : DIRECTION_BACKWARD)))
// Set backlash direction
backlashDirections[i] = lowerNewValue ? NEGATIVE : POSITIVE;
// Set that value is invalid
currentStateOfValues[i] = INVALID;
}
}
}
// Disable saving motors state
tc_set_overflow_interrupt_level(&MOTORS_SAVE_TIMER, TC_INT_LVL_OFF);
// Set current value
currentValues[i] = newValues[i];
// Enable saving motors state
tc_set_overflow_interrupt_level(&MOTORS_SAVE_TIMER, TC_INT_LVL_LO);
}
}
// Check if performing a task
if(tasks) {
// Check if bed leveling and skew aren't being compensated
if(!(tasks & BED_LEVELING_AND_SKEW_TASK)) {
// Set that X, Y, and Z are invalid
memset(currentStateOfValues, INVALID, sizeof(currentStateOfValues));
memset(validValues, INVALID, sizeof(validValues));
}
// Check if backlash compensation is enabled
#if ENABLE_BACKLASH_COMPENSATION == true
// Check if compensating for backlash and it's applicable
if(tasks & BACKLASH_TASK && (backlashDirections[X] != NONE || backlashDirections[Y] != NONE))
// Compensate for backlash
compensateForBacklash(backlashDirections[X], backlashDirections[Y]);
#endif
// Split up movement and compensate for bed leveling and skew if set
splitUpMovement(tasks & BED_LEVELING_AND_SKEW_TASK);
// Go through X and Y motors
for(uint8_t i = X; i <= Y; ++i)
// Check if motor direction changed
if(backlashDirections[i] != NONE)
// Set motor direction
currentMotorDirections[i] = backlashDirections[i] == NEGATIVE ? (i == X ? DIRECTION_LEFT : DIRECTION_FORWARD) : (i == X ? DIRECTION_RIGHT : DIRECTION_BACKWARD);
// Check if an emergency stop didn't happen
if(!emergencyStopRequest)
// Restore motors validities
memcpy(currentStateOfValues, validValues, sizeof(validValues));
}
// Otherwise check if an emergency stop didn't happen
else if(!emergencyStopRequest) {
// Initialize variables
float motorVoltageE;
// Go through all motors
for(uint8_t i = 0; i < NUMBER_OF_MOTORS; ++i)
// Check if motor moves
if(motorsIsMoving[i]) {
// Set motor delay and skip to achieve desired feed rate
setMotorDelayAndSkip(static_cast<Axes>(i), movementsHighestNumberOfCycles);
// Set motor Vref to active
switch(i) {
case X:
tc_write_cc(&MOTORS_VREF_TIMER, MOTOR_X_VREF_CHANNEL, round(MOTOR_X_CURRENT_ACTIVE * MOTORS_CURRENT_TO_VOLTAGE_SCALAR / MICROCONTROLLER_VOLTAGE * MOTORS_VREF_TIMER_PERIOD));
break;
case Y:
tc_write_cc(&MOTORS_VREF_TIMER, MOTOR_Y_VREF_CHANNEL, round(MOTOR_Y_CURRENT_ACTIVE * MOTORS_CURRENT_TO_VOLTAGE_SCALAR / MICROCONTROLLER_VOLTAGE * MOTORS_VREF_TIMER_PERIOD));
break;
case Z:
tc_write_cc(&MOTORS_VREF_TIMER, MOTOR_Z_VREF_CHANNEL, round(MOTOR_Z_CURRENT_ACTIVE * MOTORS_CURRENT_TO_VOLTAGE_SCALAR / MICROCONTROLLER_VOLTAGE * MOTORS_VREF_TIMER_PERIOD));
break;
case E:
default:
// Set motor E voltage
uint16_t motorCurrentE;
nvm_eeprom_read_buffer(EEPROM_E_MOTOR_CURRENT_OFFSET, &motorCurrentE, EEPROM_E_MOTOR_CURRENT_LENGTH);
motorVoltageE = MOTORS_CURRENT_TO_VOLTAGE_SCALAR / 1000 * motorCurrentE;
tc_write_cc(&MOTORS_VREF_TIMER, MOTOR_E_VREF_CHANNEL, round(motorVoltageE / MICROCONTROLLER_VOLTAGE * MOTORS_VREF_TIMER_PERIOD));
}
}
// Wait enough time for motor voltages to stabilize
delayMicroseconds(500);
// Start motors step timer
startMotorsStepTimer();
// Wait until all motors stop moving or an emergency stop occurs
while(areMotorsMoving() && !emergencyStopRequest) {
// Check if regulating extruder current
#if REGULATE_EXTRUDER_CURRENT == true
// Check if motor E is moving