/
main_controller_teensy41.ino
2040 lines (1900 loc) · 84.7 KB
/
main_controller_teensy41.ino
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
#include <PacketSerial.h>
#include <FastLED.h>
#include <SPI.h>
#include "TMC4361A.h"
#include "TMC4361A_TMC2660_Utils.h"
#include "crc8.h"
//#include "def_octopi.h"
#include "def_octopi_80120.h"
//#include "def_gravitymachine.h"
//#include "def_squid.h"
//#include "def_platereader.h"
//#include "def_squid_vertical.h"
#define N_MOTOR 3
#define DEBUG_MODE false
/***************************************************************************************************/
/***************************************** Communications ******************************************/
/***************************************************************************************************/
// byte[0]: which motor to move: 0 x, 1 y, 2 z, 3 LED, 4 Laser
// byte[1]: what direction: 1 forward, 0 backward
// byte[2]: how many micro steps - upper 8 bits
// byte[3]: how many micro steps - lower 8 bits
static const int CMD_LENGTH = 8;
static const int MSG_LENGTH = 24;
byte buffer_rx[512];
byte buffer_tx[MSG_LENGTH];
volatile int buffer_rx_ptr;
static const int N_BYTES_POS = 4;
byte cmd_id = 0;
bool mcu_cmd_execution_in_progress = false;
bool checksum_error = false;
// command sets
static const int MOVE_X = 0;
static const int MOVE_Y = 1;
static const int MOVE_Z = 2;
static const int MOVE_THETA = 3;
static const int HOME_OR_ZERO = 5;
static const int MOVETO_X = 6;
static const int MOVETO_Y = 7;
static const int MOVETO_Z = 8;
static const int SET_LIM = 9;
static const int TURN_ON_ILLUMINATION = 10;
static const int TURN_OFF_ILLUMINATION = 11;
static const int SET_ILLUMINATION = 12;
static const int SET_ILLUMINATION_LED_MATRIX = 13;
static const int ACK_JOYSTICK_BUTTON_PRESSED = 14;
static const int ANALOG_WRITE_ONBOARD_DAC = 15;
static const int SET_LIM_SWITCH_POLARITY = 20;
static const int CONFIGURE_STEPPER_DRIVER = 21;
static const int SET_MAX_VELOCITY_ACCELERATION = 22;
static const int SET_LEAD_SCREW_PITCH = 23;
static const int SET_OFFSET_VELOCITY = 24;
static const int CONFIGURE_STAGE_PID = 25;
static const int ENABLE_STAGE_PID = 26;
static const int DISABLE_STAGE_PID = 27;
static const int SEND_HARDWARE_TRIGGER = 30;
static const int SET_STROBE_DELAY = 31;
static const int SET_PIN_LEVEL = 41;
static const int INITIALIZE = 254;
static const int RESET = 255;
static const int COMPLETED_WITHOUT_ERRORS = 0;
static const int IN_PROGRESS = 1;
static const int CMD_CHECKSUM_ERROR = 2;
static const int CMD_INVALID = 3;
static const int CMD_EXECUTION_ERROR = 4;
static const int HOME_NEGATIVE = 1;
static const int HOME_POSITIVE = 0;
static const int HOME_OR_ZERO_ZERO = 2;
static const int AXIS_X = 0;
static const int AXIS_Y = 1;
static const int AXIS_Z = 2;
static const int AXIS_THETA = 3;
static const int AXES_XY = 4;
static const int BIT_POS_JOYSTICK_BUTTON = 0;
static const int LIM_CODE_X_POSITIVE = 0;
static const int LIM_CODE_X_NEGATIVE = 1;
static const int LIM_CODE_Y_POSITIVE = 2;
static const int LIM_CODE_Y_NEGATIVE = 3;
static const int LIM_CODE_Z_POSITIVE = 4;
static const int LIM_CODE_Z_NEGATIVE = 5;
static const int ACTIVE_LOW = 0;
static const int ACTIVE_HIGH = 1;
static const int DISABLED = 2;
/***************************************************************************************************/
/**************************************** Pin definations ******************************************/
/***************************************************************************************************/
// Teensy4.1 board v1 def
// illumination
static const int LASER_405nm = 5; // to rename
static const int LASER_488nm = 4; // to rename
static const int LASER_561nm = 22; // to rename
static const int LASER_638nm = 3; // to rename
static const int LASER_730nm = 23; // to rename
// PWM6 2
// PWM7 1
// PWM8 0
// output pins
//static const int digitial_output_pins = {2,1,6,7,8,9,10,15,24,25} // PWM 6-7, 9-16
//static const int num_digital_pins = 10;
// pin 7,8 (PWM 10, 11) may be used for UART, pin 24,25 (PWM 15, 16) may be used for UART
static const int num_digital_pins = 6;
static const int digitial_output_pins[num_digital_pins] = {2, 1, 6, 9, 10, 15}; // PWM 6-7, 9, 12-14
// camera trigger
static const int camera_trigger_pins[] = {29, 30, 31, 32, 16, 28}; // trigger 1-6
// motors
const uint8_t pin_TMC4361_CS[4] = {41, 36, 35, 34};
const uint8_t pin_TMC4361_CLK = 37;
// DAC
const int DAC8050x_CS_pin = 33;
// LED driver
const int pin_LT3932_SYNC = 25;
// power good
const int pin_PG = 0;
/***************************************************************************************************/
/************************************ camera trigger and strobe ************************************/
/***************************************************************************************************/
static const int TRIGGER_PULSE_LENGTH_us = 50;
bool trigger_output_level[6] = {HIGH, HIGH, HIGH, HIGH, HIGH, HIGH};
bool control_strobe[6] = {false, false, false, false, false, false};
bool strobe_output_level[6] = {LOW, LOW, LOW, LOW, LOW, LOW};
bool strobe_on[6] = {false, false, false, false, false, false};
int strobe_delay[6] = {0, 0, 0, 0, 0, 0};
long illumination_on_time[6] = {0, 0, 0, 0, 0, 0};
long timestamp_trigger_rising_edge[6] = {0, 0, 0, 0, 0, 0};
IntervalTimer strobeTimer;
static const int strobeTimer_interval_us = 100;
/***************************************************************************************************/
/******************************************* DAC80508 **********************************************/
/***************************************************************************************************/
const uint8_t DAC8050x_DAC_ADDR = 0x08;
const uint8_t DAC8050x_GAIN_ADDR = 0x04;
const uint8_t DAC8050x_CONFIG_ADDR = 0x03;
void set_DAC8050x_gain()
{
uint16_t value = 0;
value = (0x00 << 8) + 0x80; // REFDIV-E = 0 (no div), BUFF0-GAIN = 0 (no gain) for channel 0-6, 2 for channel 7
SPI.beginTransaction(SPISettings(1000000, MSBFIRST, SPI_MODE2));
digitalWrite(DAC8050x_CS_pin, LOW);
SPI.transfer(DAC8050x_GAIN_ADDR);
SPI.transfer16(value);
digitalWrite(DAC8050x_CS_pin, HIGH);
SPI.endTransaction();
}
void set_DAC8050x_config()
{
uint16_t value = 0;
SPI.beginTransaction(SPISettings(1000000, MSBFIRST, SPI_MODE2));
digitalWrite(DAC8050x_CS_pin, LOW);
SPI.transfer(DAC8050x_CONFIG_ADDR);
SPI.transfer16(value);
digitalWrite(DAC8050x_CS_pin, HIGH);
SPI.endTransaction();
}
void set_DAC8050x_output(int channel, uint16_t value)
{
SPI.beginTransaction(SPISettings(1000000, MSBFIRST, SPI_MODE2));
digitalWrite(DAC8050x_CS_pin, LOW);
SPI.transfer(DAC8050x_DAC_ADDR + channel);
SPI.transfer16(value);
digitalWrite(DAC8050x_CS_pin, HIGH);
SPI.endTransaction();
}
/***************************************************************************************************/
/******************************************* steppers **********************************************/
/***************************************************************************************************/
const uint32_t clk_Hz_TMC4361 = 16000000;
const uint8_t lft_sw_pol[4] = {0, 0, 0, 1};
const uint8_t rht_sw_pol[4] = {0, 0, 0, 1};
const uint8_t TMC4361_homing_sw[4] = {LEFT_SW, LEFT_SW, RGHT_SW, LEFT_SW};
const int32_t vslow = 0x04FFFC00;
ConfigurationTypeDef tmc4361_configs[N_MOTOR];
TMC4361ATypeDef tmc4361[N_MOTOR];
volatile long X_commanded_target_position = 0;
volatile long Y_commanded_target_position = 0;
volatile long Z_commanded_target_position = 0;
volatile bool X_commanded_movement_in_progress = false;
volatile bool Y_commanded_movement_in_progress = false;
volatile bool Z_commanded_movement_in_progress = false;
int X_direction;
int Y_direction;
int Z_direction;
int32_t focusPosition = 0;
long target_position;
volatile int32_t X_pos = 0;
volatile int32_t Y_pos = 0;
volatile int32_t Z_pos = 0;
float offset_velocity_x = 0;
float offset_velocity_y = 0;
bool closed_loop_position_control = false;
// limit swittch
bool is_homing_X = false;
bool is_homing_Y = false;
bool is_homing_Z = false;
bool is_homing_XY = false;
volatile bool home_X_found = false;
volatile bool home_Y_found = false;
volatile bool home_Z_found = false;
bool is_preparing_for_homing_X = false;
bool is_preparing_for_homing_Y = false;
bool is_preparing_for_homing_Z = false;
bool homing_direction_X;
bool homing_direction_Y;
bool homing_direction_Z;
elapsedMicros us_since_x_home_found;
elapsedMicros us_since_y_home_found;
elapsedMicros us_since_z_home_found;
/* to do: move the movement direction sign from configuration.txt (python) to the firmware (with
setPinsInverted() so that homing_direction_X, homing_direction_Y, homing_direction_Z will no
longer be needed. This way the home switches can act as limit switches - right now because
homing_direction_ needs be set by the computer, before they're set, the home switches cannot be
used as limit switches. Alternatively, add homing_direction_set variables.
*/
long X_POS_LIMIT = X_POS_LIMIT_MM * steps_per_mm_X;
long X_NEG_LIMIT = X_NEG_LIMIT_MM * steps_per_mm_X;
long Y_POS_LIMIT = Y_POS_LIMIT_MM * steps_per_mm_Y;
long Y_NEG_LIMIT = Y_NEG_LIMIT_MM * steps_per_mm_Y;
long Z_POS_LIMIT = Z_POS_LIMIT_MM * steps_per_mm_Z;
long Z_NEG_LIMIT = Z_NEG_LIMIT_MM * steps_per_mm_Z;
// PID
bool stage_PID_enabled[N_MOTOR];
/***************************************************************************************************/
/******************************************** timing ***********************************************/
/***************************************************************************************************/
// IntervalTimer does not work on teensy with SPI, the below lines are to be removed
static const int TIMER_PERIOD = 500; // in us
volatile int counter_send_pos_update = 0;
volatile bool flag_send_pos_update = false;
static const int interval_send_pos_update = 10000; // in us
elapsedMicros us_since_last_pos_update;
/***************************************************************************************************/
/******************************************* joystick **********************************************/
/***************************************************************************************************/
PacketSerial joystick_packetSerial;
static const int JOYSTICK_MSG_LENGTH = 10;
bool flag_read_joystick = false;
// joystick xy
int16_t joystick_delta_x = 0;
int16_t joystick_delta_y = 0;
// joystick button
bool joystick_button_pressed = false;
long joystick_button_pressed_timestamp = 0;
// focus
int32_t focuswheel_pos = 0;
bool first_packet_from_joystick_panel = true;
// btns
uint8_t btns;
void onJoystickPacketReceived(const uint8_t* buffer, size_t size)
{
if (size != JOYSTICK_MSG_LENGTH)
{
if (DEBUG_MODE)
Serial.println("! wrong number of bytes received !");
return;
}
// focuswheel_pos = uint32_t(buffer[0])*16777216 + uint32_t(buffer[1])*65536 + uint32_t(buffer[2])*256 + uint32_t(buffer[3]);
// focusPosition = focuswheel_pos;
if (first_packet_from_joystick_panel)
{
focuswheel_pos = int32_t(uint32_t(buffer[0]) * 16777216 + uint32_t(buffer[1]) * 65536 + uint32_t(buffer[2]) * 256 + uint32_t(buffer[3]));
first_packet_from_joystick_panel = false;
}
else
{
focusPosition = focusPosition + ( int32_t(uint32_t(buffer[0]) * 16777216 + uint32_t(buffer[1]) * 65536 + uint32_t(buffer[2]) * 256 + uint32_t(buffer[3])) - focuswheel_pos );
focuswheel_pos = int32_t(uint32_t(buffer[0]) * 16777216 + uint32_t(buffer[1]) * 65536 + uint32_t(buffer[2]) * 256 + uint32_t(buffer[3]));
}
joystick_delta_x = JOYSTICK_SIGN_X * int16_t( uint16_t(buffer[4]) * 256 + uint16_t(buffer[5]) );
joystick_delta_y = JOYSTICK_SIGN_Y * int16_t( uint16_t(buffer[6]) * 256 + uint16_t(buffer[7]) );
btns = buffer[8];
// temporary
/*
if(btns & 0x01)
{
joystick_button_pressed = true;
joystick_button_pressed_timestamp = millis();
// to add: ACK for the joystick panel
}
*/
flag_read_joystick = true;
}
/***************************************************************************************************/
/***************************************** illumination ********************************************/
/***************************************************************************************************/
int illumination_source = 0;
uint16_t illumination_intensity = 65535;
uint8_t led_matrix_r = 0;
uint8_t led_matrix_g = 0;
uint8_t led_matrix_b = 0;
static const int LED_MATRIX_MAX_INTENSITY = 100;
static const float GREEN_ADJUSTMENT_FACTOR = 1;
static const float RED_ADJUSTMENT_FACTOR = 1;
static const float BLUE_ADJUSTMENT_FACTOR = 1;
bool illumination_is_on = false;
void turn_on_illumination();
void turn_off_illumination();
static const int ILLUMINATION_SOURCE_LED_ARRAY_FULL = 0;
static const int ILLUMINATION_SOURCE_LED_ARRAY_LEFT_HALF = 1;
static const int ILLUMINATION_SOURCE_LED_ARRAY_RIGHT_HALF = 2;
static const int ILLUMINATION_SOURCE_LED_ARRAY_LEFTB_RIGHTR = 3;
static const int ILLUMINATION_SOURCE_LED_ARRAY_LOW_NA = 4;
static const int ILLUMINATION_SOURCE_LED_EXTERNAL_FET = 20;
static const int ILLUMINATION_SOURCE_LED_ARRAY_LEFT_DOT = 5;
static const int ILLUMINATION_SOURCE_LED_ARRAY_RIGHT_DOT = 6;
static const int ILLUMINATION_SOURCE_405NM = 11;
static const int ILLUMINATION_SOURCE_488NM = 12;
static const int ILLUMINATION_SOURCE_638NM = 13;
static const int ILLUMINATION_SOURCE_561NM = 14;
static const int ILLUMINATION_SOURCE_730NM = 15;
#define NUM_LEDS DOTSTAR_NUM_LEDS
#define LED_MATRIX_DATA_PIN 26
#define LED_MATRIX_CLOCK_PIN 27
CRGB matrix[NUM_LEDS];
void set_all(CRGB * matrix, uint8_t r, uint8_t g, uint8_t b);
void set_left(CRGB * matrix, uint8_t r, uint8_t g, uint8_t b);
void set_right(CRGB * matrix, uint8_t r, uint8_t g, uint8_t b);
void set_low_na(CRGB * matrix, uint8_t r, uint8_t g, uint8_t b);
void set_left_dot(CRGB * matrix, uint8_t r, uint8_t g, uint8_t b);
void set_right_dot(CRGB * matrix, uint8_t r, uint8_t g, uint8_t b);
void clear_matrix(CRGB * matrix);
void turn_on_LED_matrix_pattern(CRGB * matrix, int pattern, uint8_t led_matrix_r, uint8_t led_matrix_g, uint8_t led_matrix_b);
void turn_on_illumination()
{
illumination_is_on = true;
switch (illumination_source)
{
case ILLUMINATION_SOURCE_LED_ARRAY_FULL:
turn_on_LED_matrix_pattern(matrix, ILLUMINATION_SOURCE_LED_ARRAY_FULL, led_matrix_r, led_matrix_g, led_matrix_b);
break;
case ILLUMINATION_SOURCE_LED_ARRAY_LEFT_HALF:
turn_on_LED_matrix_pattern(matrix, ILLUMINATION_SOURCE_LED_ARRAY_LEFT_HALF, led_matrix_r, led_matrix_g, led_matrix_b);
break;
case ILLUMINATION_SOURCE_LED_ARRAY_RIGHT_HALF:
turn_on_LED_matrix_pattern(matrix, ILLUMINATION_SOURCE_LED_ARRAY_RIGHT_HALF, led_matrix_r, led_matrix_g, led_matrix_b);
break;
case ILLUMINATION_SOURCE_LED_ARRAY_LEFTB_RIGHTR:
turn_on_LED_matrix_pattern(matrix, ILLUMINATION_SOURCE_LED_ARRAY_LEFTB_RIGHTR, led_matrix_r, led_matrix_g, led_matrix_b);
break;
case ILLUMINATION_SOURCE_LED_ARRAY_LOW_NA:
turn_on_LED_matrix_pattern(matrix, ILLUMINATION_SOURCE_LED_ARRAY_LOW_NA, led_matrix_r, led_matrix_g, led_matrix_b);
break;
case ILLUMINATION_SOURCE_LED_ARRAY_LEFT_DOT:
turn_on_LED_matrix_pattern(matrix, ILLUMINATION_SOURCE_LED_ARRAY_LEFT_DOT, led_matrix_r, led_matrix_g, led_matrix_b);
break;
case ILLUMINATION_SOURCE_LED_ARRAY_RIGHT_DOT:
turn_on_LED_matrix_pattern(matrix, ILLUMINATION_SOURCE_LED_ARRAY_RIGHT_DOT, led_matrix_r, led_matrix_g, led_matrix_b);
break;
case ILLUMINATION_SOURCE_LED_EXTERNAL_FET:
break;
case ILLUMINATION_SOURCE_405NM:
digitalWrite(LASER_405nm, HIGH);
break;
case ILLUMINATION_SOURCE_488NM:
digitalWrite(LASER_488nm, HIGH);
break;
case ILLUMINATION_SOURCE_638NM:
digitalWrite(LASER_638nm, HIGH);
break;
case ILLUMINATION_SOURCE_561NM:
digitalWrite(LASER_561nm, HIGH);
break;
case ILLUMINATION_SOURCE_730NM:
digitalWrite(LASER_730nm, HIGH);
break;
}
}
void turn_off_illumination()
{
switch (illumination_source)
{
case ILLUMINATION_SOURCE_LED_ARRAY_FULL:
clear_matrix(matrix);
break;
case ILLUMINATION_SOURCE_LED_ARRAY_LEFT_HALF:
clear_matrix(matrix);
break;
case ILLUMINATION_SOURCE_LED_ARRAY_RIGHT_HALF:
clear_matrix(matrix);
break;
case ILLUMINATION_SOURCE_LED_ARRAY_LEFTB_RIGHTR:
clear_matrix(matrix);
break;
case ILLUMINATION_SOURCE_LED_ARRAY_LOW_NA:
clear_matrix(matrix);
break;
case ILLUMINATION_SOURCE_LED_ARRAY_LEFT_DOT:
clear_matrix(matrix);
break;
case ILLUMINATION_SOURCE_LED_ARRAY_RIGHT_DOT:
clear_matrix(matrix);
break;
case ILLUMINATION_SOURCE_LED_EXTERNAL_FET:
break;
case ILLUMINATION_SOURCE_405NM:
digitalWrite(LASER_405nm, LOW);
break;
case ILLUMINATION_SOURCE_488NM:
digitalWrite(LASER_488nm, LOW);
break;
case ILLUMINATION_SOURCE_638NM:
digitalWrite(LASER_638nm, LOW);
break;
case ILLUMINATION_SOURCE_561NM:
digitalWrite(LASER_561nm, LOW);
break;
case ILLUMINATION_SOURCE_730NM:
digitalWrite(LASER_730nm, LOW);
break;
}
illumination_is_on = false;
}
void set_illumination(int source, uint16_t intensity)
{
illumination_source = source;
illumination_intensity = intensity * 0.6;
switch (source)
{
case ILLUMINATION_SOURCE_405NM:
set_DAC8050x_output(0, illumination_intensity);
break;
case ILLUMINATION_SOURCE_488NM:
set_DAC8050x_output(1, illumination_intensity);
break;
case ILLUMINATION_SOURCE_638NM:
set_DAC8050x_output(3, illumination_intensity);
break;
case ILLUMINATION_SOURCE_561NM:
set_DAC8050x_output(2, illumination_intensity);
break;
case ILLUMINATION_SOURCE_730NM:
set_DAC8050x_output(4, illumination_intensity);
break;
}
if (illumination_is_on)
turn_on_illumination(); //update the illumination
}
void set_illumination_led_matrix(int source, uint8_t r, uint8_t g, uint8_t b)
{
illumination_source = source;
led_matrix_r = r;
led_matrix_g = g;
led_matrix_b = b;
if (illumination_is_on)
turn_on_illumination(); //update the illumination
}
void ISR_strobeTimer()
{
for (int camera_channel = 0; camera_channel < 6; camera_channel++)
{
// strobe pulse
if (control_strobe[camera_channel])
{
if (illumination_on_time[camera_channel] <= 30000)
{
// if the illumination on time is smaller than 30 ms, use delayMicroseconds to control the pulse length to avoid pulse length jitter
if ( ((micros() - timestamp_trigger_rising_edge[camera_channel]) >= strobe_delay[camera_channel]) && strobe_output_level[camera_channel] == LOW )
{
turn_on_illumination();
delayMicroseconds(illumination_on_time[camera_channel]);
turn_off_illumination();
control_strobe[camera_channel] = false;
}
}
else
{
// start the strobe
if ( ((micros() - timestamp_trigger_rising_edge[camera_channel]) >= strobe_delay[camera_channel]) && strobe_output_level[camera_channel] == LOW )
{
turn_on_illumination();
strobe_output_level[camera_channel] = HIGH;
}
// end the strobe
if (((micros() - timestamp_trigger_rising_edge[camera_channel]) >= strobe_delay[camera_channel] + illumination_on_time[camera_channel]) && strobe_output_level[camera_channel] == HIGH)
{
turn_off_illumination();
strobe_output_level[camera_channel] = LOW;
control_strobe[camera_channel] = false;
}
}
}
}
}
/***************************************************************************************************/
/********************************************* setup ***********************************************/
/***************************************************************************************************/
void setup() {
// Initialize Native USB port
SerialUSB.begin(2000000);
delay(500);
SerialUSB.setTimeout(200);
//while(!SerialUSB); // Wait until connection is established
buffer_rx_ptr = 0;
// Joystick packet serial
Serial5.begin(115200);
joystick_packetSerial.setStream(&Serial5);
joystick_packetSerial.setPacketHandler(&onJoystickPacketReceived);
// power good pin
pinMode(pin_PG, INPUT_PULLUP);
// camera trigger pins
for (int i = 0; i < 6; i++)
{
pinMode(camera_trigger_pins[i], OUTPUT);
digitalWrite(camera_trigger_pins[i], HIGH);
}
// enable pins
pinMode(LASER_405nm, OUTPUT);
digitalWrite(LASER_405nm, LOW);
pinMode(LASER_488nm, OUTPUT);
digitalWrite(LASER_488nm, LOW);
pinMode(LASER_638nm, OUTPUT);
digitalWrite(LASER_638nm, LOW);
pinMode(LASER_561nm, OUTPUT);
digitalWrite(LASER_561nm, LOW);
pinMode(LASER_730nm, OUTPUT);
digitalWrite(LASER_730nm, LOW);
for (int i = 0; i < num_digital_pins; i++)
{
pinMode(digitial_output_pins[i], OUTPUT);
digitalWrite(digitial_output_pins[i], LOW);
}
// steppers pins
for (int i = 0; i < 4; i++)
{
pinMode(pin_TMC4361_CS[i], OUTPUT);
digitalWrite(pin_TMC4361_CS[i], HIGH);
}
// LED drivers
pinMode(pin_LT3932_SYNC, OUTPUT);
analogWriteFrequency(pin_LT3932_SYNC, 2000000);
analogWrite(pin_LT3932_SYNC, 128);
// timer - does not work with SPI
/*
IntervalTimer systemTimer;
systemTimer.begin(timer_interruptHandler, TIMER_PERIOD);
*/
// DAC pins
pinMode(DAC8050x_CS_pin, OUTPUT);
digitalWrite(DAC8050x_CS_pin, HIGH);
// wait for PG to turn high
delay(100);
while (!digitalRead(pin_PG))
{
delay(50);
}
/*********************************************************************************************************
************************************** TMC4361A + TMC2660 beginning *************************************
*********************************************************************************************************/
// PID
for (int i = 0; i < N_MOTOR; i++)
stage_PID_enabled[i] = 0;
// clock
pinMode(pin_TMC4361_CLK, OUTPUT);
analogWriteFrequency(pin_TMC4361_CLK, clk_Hz_TMC4361);
analogWrite(pin_TMC4361_CLK, 128); // 50% duty
// initialize TMC4361 structs with default values and initialize CS pins
for (int i = 0; i < N_MOTOR; i++)
{
// initialize the tmc4361 with their channel number and default configuration
tmc4361A_init(&tmc4361[i], pin_TMC4361_CS[i], &tmc4361_configs[i], tmc4361A_defaultRegisterResetState);
// set the chip select pins
pinMode(pin_TMC4361_CS[i], OUTPUT);
digitalWrite(pin_TMC4361_CS[i], HIGH);
}
// motor configurations
tmc4361A_tmc2660_config(&tmc4361[x], (X_MOTOR_RMS_CURRENT_mA / 1000)*R_sense_xy / 0.2298, X_MOTOR_I_HOLD, 1, 1, 1, SCREW_PITCH_X_MM, FULLSTEPS_PER_REV_X, MICROSTEPPING_X);
tmc4361A_tmc2660_config(&tmc4361[y], (Y_MOTOR_RMS_CURRENT_mA / 1000)*R_sense_xy / 0.2298, Y_MOTOR_I_HOLD, 1, 1, 1, SCREW_PITCH_Y_MM, FULLSTEPS_PER_REV_Y, MICROSTEPPING_Y);
tmc4361A_tmc2660_config(&tmc4361[z], (Z_MOTOR_RMS_CURRENT_mA / 1000)*R_sense_z / 0.2298, Z_MOTOR_I_HOLD, 1, 1, 1, SCREW_PITCH_Z_MM, FULLSTEPS_PER_REV_Z, MICROSTEPPING_Z); // need to make current scaling on TMC2660 is > 16 (out of 31)
// SPI
SPI.begin();
delayMicroseconds(5000);
// initilize TMC4361 and TMC2660 - turn on functionality
for (int i = 0; i < N_MOTOR; i++)
tmc4361A_tmc2660_init(&tmc4361[i], clk_Hz_TMC4361); // set up ICs with SPI control and other parameters
// enable limit switch reading
tmc4361A_enableLimitSwitch(&tmc4361[x], lft_sw_pol[x], LEFT_SW, flip_limit_switch_x);
tmc4361A_enableLimitSwitch(&tmc4361[x], rht_sw_pol[x], RGHT_SW, flip_limit_switch_x);
tmc4361A_enableLimitSwitch(&tmc4361[y], lft_sw_pol[y], LEFT_SW, flip_limit_switch_y);
tmc4361A_enableLimitSwitch(&tmc4361[y], rht_sw_pol[y], RGHT_SW, flip_limit_switch_y);
tmc4361A_enableLimitSwitch(&tmc4361[z], rht_sw_pol[z], RGHT_SW, false);
tmc4361A_enableLimitSwitch(&tmc4361[z], lft_sw_pol[z], LEFT_SW, false); // removing this causes z homing to not work properly
// tmc4361A_rstBits(&tmc4361[z],TMC4361A_REFERENCE_CONF,TMC4361A_STOP_LEFT_EN_MASK);
// motion profile configuration
uint32_t max_velocity_usteps[N_MOTOR];
uint32_t max_acceleration_usteps[N_MOTOR];
max_acceleration_usteps[x] = tmc4361A_ammToMicrosteps(&tmc4361[x], MAX_ACCELERATION_X_mm);
max_acceleration_usteps[y] = tmc4361A_ammToMicrosteps(&tmc4361[y], MAX_ACCELERATION_Y_mm);
max_acceleration_usteps[z] = tmc4361A_ammToMicrosteps(&tmc4361[z], MAX_ACCELERATION_Z_mm);
max_velocity_usteps[x] = tmc4361A_vmmToMicrosteps(&tmc4361[x], MAX_VELOCITY_X_mm);
max_velocity_usteps[y] = tmc4361A_vmmToMicrosteps(&tmc4361[y], MAX_VELOCITY_Y_mm);
max_velocity_usteps[z] = tmc4361A_vmmToMicrosteps(&tmc4361[z], MAX_VELOCITY_Z_mm);
for (int i = 0; i < N_MOTOR; i++)
{
// initialize ramp with default values
tmc4361A_setMaxSpeed(&tmc4361[i], max_velocity_usteps[i]);
tmc4361A_setMaxAcceleration(&tmc4361[i], max_acceleration_usteps[i]);
tmc4361[i].rampParam[ASTART_IDX] = 0;
tmc4361[i].rampParam[DFINAL_IDX] = 0;
tmc4361A_sRampInit(&tmc4361[i]);
}
/*
// homing - temporary
tmc4361A_enableHomingLimit(&tmc4361[x], lft_sw_pol[x], TMC4361_homing_sw[x]);
tmc4361A_moveToExtreme(&tmc4361[x], vslow*2, RGHT_DIR);
tmc4361A_moveToExtreme(&tmc4361[x], vslow*2, LEFT_DIR);
tmc4361A_setHome(&tmc4361[x]);
tmc4361A_enableHomingLimit(&tmc4361[y], lft_sw_pol[y], TMC4361_homing_sw[y]);
tmc4361A_moveToExtreme(&tmc4361[y], vslow*2, RGHT_DIR);
tmc4361A_moveToExtreme(&tmc4361[y], vslow*2, LEFT_DIR);
tmc4361A_setHome(&tmc4361[y]);
*/
// homing switch settings
tmc4361A_enableHomingLimit(&tmc4361[x], lft_sw_pol[x], TMC4361_homing_sw[x]);
tmc4361A_enableHomingLimit(&tmc4361[y], lft_sw_pol[y], TMC4361_homing_sw[y]);
tmc4361A_enableHomingLimit(&tmc4361[z], rht_sw_pol[z], TMC4361_homing_sw[z]);
/*********************************************************************************************************
***************************************** TMC4361A + TMC2660 end ****************************************
*********************************************************************************************************/
// DAC init
set_DAC8050x_config();
set_DAC8050x_gain();
// led matrix
FastLED.addLeds<APA102, LED_MATRIX_DATA_PIN, LED_MATRIX_CLOCK_PIN, BGR, 1>(matrix, NUM_LEDS); // 1 MHz clock rate
// variables
X_pos = 0;
Y_pos = 0;
Z_pos = 0;
offset_velocity_x = 0;
offset_velocity_y = 0;
// strobe timer
strobeTimer.begin(ISR_strobeTimer, strobeTimer_interval_us);
// motor stall prevention
tmc4361A_config_init_stallGuard(&tmc4361[x], 12, true, 1);
tmc4361A_config_init_stallGuard(&tmc4361[y], 12, true, 1);
}
/***************************************************************************************************/
/********************************************** loop ***********************************************/
/***************************************************************************************************/
void loop() {
// process incoming packets
joystick_packetSerial.update();
// read one meesage from the buffer
while (SerialUSB.available())
{
buffer_rx[buffer_rx_ptr] = SerialUSB.read();
buffer_rx_ptr = buffer_rx_ptr + 1;
if (buffer_rx_ptr == CMD_LENGTH)
{
buffer_rx_ptr = 0;
cmd_id = buffer_rx[0];
uint8_t checksum = crc8ccitt(buffer_rx, CMD_LENGTH - 1);
if (checksum != buffer_rx[CMD_LENGTH - 1])
{
checksum_error = true;
// empty the serial buffer because byte-level out-of-sync can also cause this error
while (SerialUSB.available())
SerialUSB.read();
return;
}
else
{
checksum_error = false;
}
switch (buffer_rx[1])
{
case MOVE_X:
{
long relative_position = int32_t(uint32_t(buffer_rx[2]) * 16777216 + uint32_t(buffer_rx[3]) * 65536 + uint32_t(buffer_rx[4]) * 256 + uint32_t(buffer_rx[5]));
long current_position = tmc4361A_currentPosition(&tmc4361[x]);
X_direction = sgn(relative_position);
X_commanded_target_position = ( relative_position > 0 ? min(current_position + relative_position, X_POS_LIMIT) : max(current_position + relative_position, X_NEG_LIMIT) );
if ( tmc4361A_moveTo(&tmc4361[x], X_commanded_target_position) == 0)
{
X_commanded_movement_in_progress = true;
mcu_cmd_execution_in_progress = true;
}
break;
}
case MOVE_Y:
{
long relative_position = int32_t(uint32_t(buffer_rx[2]) * 16777216 + uint32_t(buffer_rx[3]) * 65536 + uint32_t(buffer_rx[4]) * 256 + uint32_t(buffer_rx[5]));
long current_position = tmc4361A_currentPosition(&tmc4361[y]);
Y_direction = sgn(relative_position);
Y_commanded_target_position = ( relative_position > 0 ? min(current_position + relative_position, Y_POS_LIMIT) : max(current_position + relative_position, Y_NEG_LIMIT) );
if ( tmc4361A_moveTo(&tmc4361[y], Y_commanded_target_position) == 0)
{
Y_commanded_movement_in_progress = true;
mcu_cmd_execution_in_progress = true;
}
break;
}
case MOVE_Z:
{
long relative_position = int32_t(uint32_t(buffer_rx[2]) * 16777216 + uint32_t(buffer_rx[3]) * 65536 + uint32_t(buffer_rx[4]) * 256 + uint32_t(buffer_rx[5]));
long current_position = tmc4361A_currentPosition(&tmc4361[z]);
Z_direction = sgn(relative_position);
Z_commanded_target_position = ( relative_position > 0 ? min(current_position + relative_position, Z_POS_LIMIT) : max(current_position + relative_position, Z_NEG_LIMIT) );
focusPosition = Z_commanded_target_position;
if ( tmc4361A_moveTo(&tmc4361[z], Z_commanded_target_position) == 0)
{
Z_commanded_movement_in_progress = true;
mcu_cmd_execution_in_progress = true;
}
break;
}
case MOVETO_X:
{
long absolute_position = int32_t(uint32_t(buffer_rx[2]) * 16777216 + uint32_t(buffer_rx[3]) * 65536 + uint32_t(buffer_rx[4]) * 256 + uint32_t(buffer_rx[5]));
X_direction = sgn(absolute_position - tmc4361A_currentPosition(&tmc4361[x]));
X_commanded_target_position = absolute_position;
if (tmc4361A_moveTo(&tmc4361[x], X_commanded_target_position) == 0)
{
X_commanded_movement_in_progress = true;
mcu_cmd_execution_in_progress = true;
}
break;
}
case MOVETO_Y:
{
long absolute_position = int32_t(uint32_t(buffer_rx[2]) * 16777216 + uint32_t(buffer_rx[3]) * 65536 + uint32_t(buffer_rx[4]) * 256 + uint32_t(buffer_rx[5]));
Y_direction = sgn(absolute_position - tmc4361A_currentPosition(&tmc4361[y]));
Y_commanded_target_position = absolute_position;
if (tmc4361A_moveTo(&tmc4361[y], Y_commanded_target_position) == 0)
{
Y_commanded_movement_in_progress = true;
mcu_cmd_execution_in_progress = true;
}
break;
}
case MOVETO_Z:
{
long absolute_position = int32_t(uint32_t(buffer_rx[2]) * 16777216 + uint32_t(buffer_rx[3]) * 65536 + uint32_t(buffer_rx[4]) * 256 + uint32_t(buffer_rx[5]));
Z_direction = sgn(absolute_position - tmc4361A_currentPosition(&tmc4361[z]));
Z_commanded_target_position = absolute_position;
if (tmc4361A_moveTo(&tmc4361[z], Z_commanded_target_position) == 0)
{
focusPosition = absolute_position;
Z_commanded_movement_in_progress = true;
mcu_cmd_execution_in_progress = true;
}
break;
}
case SET_LIM:
{
switch (buffer_rx[2])
{
case LIM_CODE_X_POSITIVE:
{
X_POS_LIMIT = int32_t(uint32_t(buffer_rx[3]) * 16777216 + uint32_t(buffer_rx[4]) * 65536 + uint32_t(buffer_rx[5]) * 256 + uint32_t(buffer_rx[6]));
tmc4361A_setVirtualLimit(&tmc4361[x], 1, X_POS_LIMIT);
tmc4361A_enableVirtualLimitSwitch(&tmc4361[x], 1);
break;
}
case LIM_CODE_X_NEGATIVE:
{
X_NEG_LIMIT = int32_t(uint32_t(buffer_rx[3]) * 16777216 + uint32_t(buffer_rx[4]) * 65536 + uint32_t(buffer_rx[5]) * 256 + uint32_t(buffer_rx[6]));
tmc4361A_setVirtualLimit(&tmc4361[x], -1, X_NEG_LIMIT);
tmc4361A_enableVirtualLimitSwitch(&tmc4361[x], -1);
break;
}
case LIM_CODE_Y_POSITIVE:
{
Y_POS_LIMIT = int32_t(uint32_t(buffer_rx[3]) * 16777216 + uint32_t(buffer_rx[4]) * 65536 + uint32_t(buffer_rx[5]) * 256 + uint32_t(buffer_rx[6]));
tmc4361A_setVirtualLimit(&tmc4361[y], 1, Y_POS_LIMIT);
tmc4361A_enableVirtualLimitSwitch(&tmc4361[y], 1);
break;
}
case LIM_CODE_Y_NEGATIVE:
{
Y_NEG_LIMIT = int32_t(uint32_t(buffer_rx[3]) * 16777216 + uint32_t(buffer_rx[4]) * 65536 + uint32_t(buffer_rx[5]) * 256 + uint32_t(buffer_rx[6]));
tmc4361A_setVirtualLimit(&tmc4361[y], -1, Y_NEG_LIMIT);
tmc4361A_enableVirtualLimitSwitch(&tmc4361[y], -1);
break;
}
case LIM_CODE_Z_POSITIVE:
{
Z_POS_LIMIT = int32_t(uint32_t(buffer_rx[3]) * 16777216 + uint32_t(buffer_rx[4]) * 65536 + uint32_t(buffer_rx[5]) * 256 + uint32_t(buffer_rx[6]));
tmc4361A_setVirtualLimit(&tmc4361[z], 1, Z_POS_LIMIT);
tmc4361A_enableVirtualLimitSwitch(&tmc4361[z], 1);
break;
}
case LIM_CODE_Z_NEGATIVE:
{
Z_NEG_LIMIT = int32_t(uint32_t(buffer_rx[3]) * 16777216 + uint32_t(buffer_rx[4]) * 65536 + uint32_t(buffer_rx[5]) * 256 + uint32_t(buffer_rx[6]));
tmc4361A_setVirtualLimit(&tmc4361[z], -1, Z_NEG_LIMIT);
tmc4361A_enableVirtualLimitSwitch(&tmc4361[z], -1);
break;
}
}
break;
}
case SET_LIM_SWITCH_POLARITY:
{
switch (buffer_rx[2])
{
case AXIS_X:
{
if (buffer_rx[3] != DISABLED)
{
LIM_SWITCH_X_ACTIVE_LOW = (buffer_rx[3] == ACTIVE_LOW);
}
break;
}
case AXIS_Y:
{
if (buffer_rx[3] != DISABLED)
{
LIM_SWITCH_Y_ACTIVE_LOW = (buffer_rx[3] == ACTIVE_LOW);
}
break;
}
case AXIS_Z:
{
if (buffer_rx[3] != DISABLED)
{
LIM_SWITCH_Z_ACTIVE_LOW = (buffer_rx[3] == ACTIVE_LOW);
}
break;
}
}
break;
}
case CONFIGURE_STEPPER_DRIVER:
{
switch (buffer_rx[2])
{
case AXIS_X:
{
int microstepping_setting = buffer_rx[3];
if (microstepping_setting > 128)
microstepping_setting = 256;
MICROSTEPPING_X = microstepping_setting == 0 ? 1 : microstepping_setting;
steps_per_mm_X = FULLSTEPS_PER_REV_X * MICROSTEPPING_X / SCREW_PITCH_X_MM;
X_MOTOR_RMS_CURRENT_mA = uint16_t(buffer_rx[4]) * 256 + uint16_t(buffer_rx[5]);
X_MOTOR_I_HOLD = float(buffer_rx[6]) / 255;
tmc4361A_tmc2660_config(&tmc4361[x], (X_MOTOR_RMS_CURRENT_mA / 1000.0)*R_sense_xy / 0.2298, X_MOTOR_I_HOLD, 1, 1, 1, SCREW_PITCH_X_MM, FULLSTEPS_PER_REV_X, MICROSTEPPING_X);
tmc4361A_tmc2660_update(&tmc4361[x]);
break;
}
case AXIS_Y:
{
int microstepping_setting = buffer_rx[3];
if (microstepping_setting > 128)
microstepping_setting = 256;
MICROSTEPPING_Y = microstepping_setting == 0 ? 1 : microstepping_setting;
steps_per_mm_Y = FULLSTEPS_PER_REV_Y * MICROSTEPPING_Y / SCREW_PITCH_Y_MM;
Y_MOTOR_RMS_CURRENT_mA = uint16_t(buffer_rx[4]) * 256 + uint16_t(buffer_rx[5]);
Y_MOTOR_I_HOLD = float(buffer_rx[6]) / 255;
tmc4361A_tmc2660_config(&tmc4361[y], (Y_MOTOR_RMS_CURRENT_mA / 1000.0)*R_sense_xy / 0.2298, Y_MOTOR_I_HOLD, 1, 1, 1, SCREW_PITCH_Y_MM, FULLSTEPS_PER_REV_Y, MICROSTEPPING_Y);
tmc4361A_tmc2660_update(&tmc4361[y]);
break;
}
case AXIS_Z:
{
int microstepping_setting = buffer_rx[3];
if (microstepping_setting > 128)
microstepping_setting = 256;
MICROSTEPPING_Z = microstepping_setting == 0 ? 1 : microstepping_setting;
steps_per_mm_Z = FULLSTEPS_PER_REV_Z * MICROSTEPPING_Z / SCREW_PITCH_Z_MM;
Z_MOTOR_RMS_CURRENT_mA = uint16_t(buffer_rx[4]) * 256 + uint16_t(buffer_rx[5]);
Z_MOTOR_I_HOLD = float(buffer_rx[6]) / 255;
tmc4361A_tmc2660_config(&tmc4361[z], (Z_MOTOR_RMS_CURRENT_mA / 1000.0)*R_sense_z / 0.2298, Z_MOTOR_I_HOLD, 1, 1, 1, SCREW_PITCH_Z_MM, FULLSTEPS_PER_REV_Z, MICROSTEPPING_Z);
tmc4361A_tmc2660_update(&tmc4361[z]);
break;
}
}
break;
}
case SET_MAX_VELOCITY_ACCELERATION:
{
switch (buffer_rx[2])
{
case AXIS_X:
{
MAX_VELOCITY_X_mm = float(uint16_t(buffer_rx[3]) * 256 + uint16_t(buffer_rx[4])) / 100;
MAX_ACCELERATION_X_mm = float(uint16_t(buffer_rx[5]) * 256 + uint16_t(buffer_rx[6])) / 10;
tmc4361A_setMaxSpeed(&tmc4361[x], tmc4361A_vmmToMicrosteps( &tmc4361[x], MAX_VELOCITY_X_mm) );
tmc4361A_setMaxAcceleration(&tmc4361[x], tmc4361A_ammToMicrosteps( &tmc4361[x], MAX_ACCELERATION_X_mm) );
break;
}
case AXIS_Y:
{
MAX_VELOCITY_Y_mm = float(uint16_t(buffer_rx[3]) * 256 + uint16_t(buffer_rx[4])) / 100;
MAX_ACCELERATION_Y_mm = float(uint16_t(buffer_rx[5]) * 256 + uint16_t(buffer_rx[6])) / 10;
tmc4361A_setMaxSpeed(&tmc4361[y], tmc4361A_vmmToMicrosteps( &tmc4361[y], MAX_VELOCITY_Y_mm) );
tmc4361A_setMaxAcceleration(&tmc4361[y], tmc4361A_ammToMicrosteps( &tmc4361[y], MAX_ACCELERATION_Y_mm) );
break;
}
case AXIS_Z:
{
MAX_VELOCITY_Z_mm = float(uint16_t(buffer_rx[3]) * 256 + uint16_t(buffer_rx[4])) / 100;
MAX_ACCELERATION_Z_mm = float(uint16_t(buffer_rx[5]) * 256 + uint16_t(buffer_rx[6])) / 10;
tmc4361A_setMaxSpeed(&tmc4361[z], tmc4361A_vmmToMicrosteps( &tmc4361[z], MAX_VELOCITY_Z_mm) );
tmc4361A_setMaxAcceleration(&tmc4361[z], tmc4361A_ammToMicrosteps( &tmc4361[z], MAX_ACCELERATION_Z_mm) );
break;
}
}
break;
}
case SET_LEAD_SCREW_PITCH:
{
switch (buffer_rx[2])
{
case AXIS_X: