-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathcute_avr32.c
executable file
·2121 lines (1991 loc) · 81.7 KB
/
cute_avr32.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
//-----------------------------------------------------------------------------
// File: cute_avr32.c
//
// Description: Embedded AVR32 code for the CUTE cryostat positioning system
//
// Revisions: 2011/06/03 - P.Harvey created
// 2013/06/06 - PH v1.03 - added ability to specify channel ranges in pa/pb
// 2013/10/04 - PH v1.04 - updated for Steve's new MANIP readout circuit
// 2013/10/24 - PH v1.05 - added ability to invert motor on/dir signals
// 2014/07/04 - PH v1.06 - added code to turn off DEAP valves on startup
// 2014/07/15 - PH v1.07 - disable rs232 debugging due to port conflict,
// and disable WDT LED for DEAP resurfacer
// 2014/10/14 - PH v1.08 - clear more outputs on startup
// 2016/02/29 - PH v1.09 - added SNO+ digital i/o commands and changed
// minimum motor speed to 25 steps/sec
// 2016/03/01 - PH v1.10 - added motor "run" command
// 2016/03/15 - PH v1.11 - check MAX197 INT signal to indicate conversion
// and added "p6" command
// 2016/03/17 - PH v1.12 - changed motor/pwm "run" command to "spd"
// 2017/01/30 - PH v1.13 - added ability to specify ADC range
// 2018/08/08 - PH v1.14 - added motor 0 step command
//
// Notes: The embedded software is C because the inherent indirect
// addressing of C++ objects is too inefficient
//
// The watchdog timer is set to 1 second by default, and will
// reset the AVR32 if a command is not received in this time.
// On reset, LED3 will light until a "wdt SECS" command is received. (manip only)
//
// Disclaimer: This code is very ugly and contains many duplicated sections
// because it was found that using array lookups to reduce duplicate
// code slowed things down significantly
//-----------------------------------------------------------------------------
//_____ I N C L U D E S ___________________________________________________
#include <stdio.h>
#include <string.h>
#include <ctype.h>
#include "compiler.h"
#include "board.h"
#include "print_funcs.h"
#include "intc.h"
#include "power_clocks_lib.h"
#include "gpio.h"
#include "adc.h"
#include "conf_usb.h"
#include "usb_task.h"
#include "tc.h"
#include "wdt.h"
#include "pwm.h"
#include "usb_drv.h"
#include "usb_descriptors.h"
#include "usb_standard_request.h"
//#define MANIP // for use with SNO+ manip
#define CUTE // use for CUTE expt
//#define DEBUG // enable debugging code
#define VERSION 1.14
#define NUM_MOTORS 3
#define NUM_ADCS 4
#define TC0_CHANNEL 0
#define TC1_CHANNEL 1
#define TC2_CHANNEL 2
#define IO_CHANNELS 44 // number of available I/O channels (PA0-PA31,PB0-PB11)
#define PKT_SIZE 64 // maximum USB packet size
#define FPBA FOSC0 // 12 MHz
#if defined(MANIP) || defined(CUTE)
// SNO+ manip AVR channels
#define BYSEL 16 // read byte select
#define XWR 17 // write strobe (active low)
#define XRD 20 // read strobe (active low)
#define XRST 21 // counter reset (active low)
#define DEV0 23 // device ID bit 0
#define INT 24 // MAX197 adc interrupt (active low)
#define DEV1 25 // device ID bit 1
#define BRD0 26 // board ID bit 0
#define BRD1 27 // board ID bit 1
#define BRDSEL 28 // board select
#define ENCP 29 // encoder power
#define WDAT 8 // bit 0 of write data
#define RDAT 0 // bit 0 of read data
#elif !defined(CUTE)
// DEAP output pins to clear on startup
#define kNumClearPins 14
static int sClearPin[kNumClearPins] = { 0,1,7,5,6,2,20,21,22,23,24,25,26,27 };
#endif
//_____ watchdog timer ______________________________________________
// watchdog timer delay in microseconds (note: value is rounded up to nearest available time)
#define WDT_MAX_VALUE_US 1 * 1000000L
// To specify which current Watchdog value
volatile U32 current_wdt_value = WDT_MAX_VALUE_US;
//_____ D E F I N I T I O N S ______________________________________________
#define kClockFreq 12000000L // frequency for default tc clock source (3)
#define kPrescale 8 // prescale for default clock source (3)
#define kMinTop 5 // limits maximum speed
#define kMotorAccDefault 4000 // default motor acceleration in steps/sec/sec
#define kMotorAccMin 1000 // minimum motor acceleration (steps/sec/sec)
#define kMotorAccMax 10000 // maximum motor acceleration (steps/sec/sec)
#define kMinSpeed 25 // minimum motor speed (steps/sec)
#define kInitRC kClockFreq / (kPrescale * (long)kMinSpeed) // initial RC value
#define kMaxWaitConv 40 // maximum number of loops to wait for ADC conversion
#define OUT_SIZE 1024 // size of message response buffer
__attribute__((__interrupt__)) static void m0_irq(void);
__attribute__((__interrupt__)) static void m1_irq(void);
__attribute__((__interrupt__)) static void m2_irq(void);
//_____ D E C L A R A T I O N S ____________________________________________
// motor TC initialization constants
static struct {
int channel;
int pin;
int function;
int rc;
int irqNum;
void (*irq)(void);
int dir; // PA channel for direction signal
int on; // PA channel for on signal
char dirInv; // flag for direction signal inverted
char onInv; // flag for windings on signal inverted
} sMotor[NUM_MOTORS] = {
#if defined(MANIP) || defined(CUTE)
//
// Motor definitions for SNO+ MANIP and CUTE
//
{
.channel = 0, // TC channel for this motor
.pin = AVR32_TC_A0_0_0_PIN, // PA32 (=PB00)
.function = AVR32_TC_A0_0_0_FUNCTION,
.rc = kInitRC,
.irqNum = AVR32_TC_IRQ0,
.irq = &m0_irq,
.dir = 33, // PB01
.on = 37, // PB05
// aux output PB04
.dirInv = 0,
.onInv = 1
},{
.channel = 1,
//.pin = AVR32_TC_A1_0_0_PIN, // PA21
//.function = AVR32_TC_A1_0_0_FUNCTION,
.pin = AVR32_TC_A1_0_1_PIN, // PA34 (=PB02)
.function = AVR32_TC_A1_0_1_FUNCTION,
.rc = kInitRC,
.irqNum = AVR32_TC_IRQ1,
.irq = &m1_irq,
.dir = 35, // PB03
.on = 38, // PB06
// aux output PB07
.dirInv = 0,
.onInv = 1
},{
.channel = 2,
.pin = AVR32_TC_A2_0_1_PIN, // PB10
.function = AVR32_TC_A2_0_1_FUNCTION,
.rc = kInitRC,
.irqNum = AVR32_TC_IRQ2,
.irq = &m2_irq,
.dir = 43, // PB11
.on = 40, // PB08
// aux output PB09
.dirInv = 0,
.onInv = 1
}
#else
//
// Motor definitions for DEAP resurfacer
//
{
.channel = 0, // TC channel for this motor
.pin = AVR32_TC_A0_0_0_PIN, // PA32 (=PB00)
.function = AVR32_TC_A0_0_0_FUNCTION,
.rc = kInitRC,
.irqNum = AVR32_TC_IRQ0,
.irq = &m0_irq,
.dir = 15, // PA15
.on = 14, // PA14
.dirInv = 0,
.onInv = 0
},{
.channel = 1,
//.pin = AVR32_TC_A1_0_0_PIN, // PA21
//.function = AVR32_TC_A1_0_0_FUNCTION,
.pin = AVR32_TC_A1_0_1_PIN, // PA34 (=PB02)
.function = AVR32_TC_A1_0_1_FUNCTION,
.rc = kInitRC,
.irqNum = AVR32_TC_IRQ1,
.irq = &m1_irq,
.dir = 13, // PA13
.on = 12, // PA12
.dirInv = 0,
.onInv = 0
},{
.channel = 2,
.pin = AVR32_TC_A2_0_0_PIN, // PA11
.function = AVR32_TC_A2_0_0_FUNCTION,
.rc = kInitRC,
.irqNum = AVR32_TC_IRQ2,
.irq = &m2_irq,
.dir = 10, // PA10
.on = 9, // PA09
.dirInv = 0,
.onInv = 0
}
#endif
};
static struct {
int channel;
int pin;
int function;
} sADC[NUM_ADCS] = {
{
.channel = 0,
.pin = AVR32_ADC_AD_0_PIN, // PA03
.function = AVR32_ADC_AD_0_FUNCTION,
},{
.channel = 1,
.pin = AVR32_ADC_AD_1_PIN, // PA04
.function = AVR32_ADC_AD_1_FUNCTION,
},{
.channel = 6, // 6=light sensor
.pin = AVR32_ADC_AD_6_PIN, // PA30
.function = AVR32_ADC_AD_6_FUNCTION,
},{
.channel = 7, // 7=temperature
.pin = AVR32_ADC_AD_7_PIN, // PA31
.function = AVR32_ADC_AD_7_FUNCTION,
}};
static U16 sof_cnt;
static U16 data_length;
static char has_data;
static char wdt_flag = 0; // 0=not enabled, 1=power up, 2=WDT reset
static char pwm_flag = 0; // 0=not initialized, 1=stopped, 2=running
// PIO channel output modes (0=input, 1=output, 2=input /w pull-up, 3=other function)
static char output_mode[64] = { 0 };
// configuration
#if defined(MANIP) || defined(CUTE)
#define kNumAdrLines 4
int cfg_adr[kNumAdrLines] = {
// default lines for addressing devices (add 32 for PB channels)
DEV0, DEV1, BRD0, BRD1
};
#define kNumDatLines 8
int cfg_dat[kNumDatLines] = {
// default data lines (add 32 for PB channels)
RDAT, RDAT+1, RDAT+2, RDAT+3, RDAT+4, RDAT+5, RDAT+6, RDAT+7
};
#define kNumDelay 6
int cfg_del[kNumDelay] = {
0, // counter delay after raising RST and after enable output
0, // counter delay for data to stabilize (min 65ns)
0, // adc delay before initiate conversion (min 50ns)
0, // adc delay for conversion (min 10us) [now wait for INT to go low]
0, // adc delay for data to stabilize (min 150ns)
0, // adc delay before reading low byte (min ??)
};
#define A0 cfg_adr[0]
#define A1 cfg_adr[1]
#define A2 cfg_adr[2]
#define A3 cfg_adr[3]
int dig_out[4] = { 0 }; // digital output bytes for Steve's modified board
#endif
int motor_src[5] = {
TC_CLOCK_SOURCE_TC1,
TC_CLOCK_SOURCE_TC2,
TC_CLOCK_SOURCE_TC3,
TC_CLOCK_SOURCE_TC4,
TC_CLOCK_SOURCE_TC5
};
/*int motor_freq[5] = {
32000,
12000000,
12000000,
12000000,
12000000
};
int motor_prescale[5] = {
1,
2,
8,
32,
128
};*/
// actual frequency for each tc clock source
int motor_actClock[5] = {
32768, // 32 kHz / 1
6000000, // 12 MHz / 2
1500000, // 12 MHz / 8
375000, // 12 MHz / 32
93750 // 12 MHz / 128
};
// motor variables
// NOTE: "ISR" variables are changed in interrupt routine!
long m0_motorPos = 0; // ISR motor position count
unsigned char m0_motorDir = 0; // motor direction flag
unsigned char m0_motorOn = 0; // motor on flag
unsigned char m0_ramping = 0; // ISR ramping flag
unsigned int m0_rampTo = 0; // ramp to this RC value
unsigned char m0_rampFlag = 0; // ISR flag to start ramping motor (2=stop,3=halt)
unsigned char m0_running = 0; // ISR flag that motor is running
unsigned m0_curSpeed = kMinSpeed;// ISR current speed in Hz
unsigned m0_endSpeed; // ISR ramp end speed in Hz
unsigned m0_curRC = kInitRC; // ISR current counter RC value
#ifdef DEBUG
unsigned m0_latency = 0; // ISR maximum latency of interrupt
unsigned m0_lastCount = 0; // ISR latency of last interrupt
#endif
unsigned long m0_actClock = 1500000; // actual clock freq = kClockFreq / kPrescale
unsigned m0_startSpeed; // motor start speed
unsigned int m0_acc = kMotorAccDefault; // motor acceleration (steps/s/s)
long m0_rampTime; // time motor has been ramping (TC ticks)
long m0_rampEndTime; // time at end of ramp (TC ticks)
float m0_rampScl = (float)(kClockFreq / kPrescale) / kMotorAccDefault;
int m0_minSpeed = kMinSpeed;
unsigned char m0_stopFlag = 0; // ISR flag to stop motor
unsigned char m0_stepMode = 0; // 0=done, 1=ramp up, 2=cruise, 3=ramp down
int m0_src = 3; // source clock
long m0_stepFrom; // step start
long m0_stepTo; // step end
long m0_rampEnd; // step where ramp was completed
long m0_stepNext; // step where we have to change something
long m1_motorPos = 0;
unsigned char m1_motorDir = 0;
unsigned char m1_motorOn = 0;
unsigned char m1_ramping = 0;
unsigned int m1_rampTo = 0;
unsigned char m1_rampFlag = 0;
unsigned char m1_running = 0;
unsigned m1_curSpeed = kMinSpeed;
unsigned m1_endSpeed;
unsigned m1_curRC = kInitRC;
#ifdef DEBUG
unsigned m1_latency = 0;
unsigned m1_lastCount = 0;
#endif
unsigned long m1_actClock = 1500000;
unsigned m1_startSpeed;
unsigned int m1_acc = kMotorAccDefault;
long m1_rampTime;
long m1_rampEndTime;
float m1_rampScl = (float)(kClockFreq / kPrescale) / kMotorAccDefault;
int m1_minSpeed = kMinSpeed;
unsigned char m1_stopFlag = 0;
int m1_src = 3; // source clock
long m2_motorPos = 0;
unsigned char m2_motorDir = 0;
unsigned char m2_motorOn = 0;
unsigned char m2_ramping = 0;
unsigned int m2_rampTo = 0;
unsigned char m2_rampFlag = 0;
unsigned char m2_running = 0;
unsigned m2_curSpeed = kMinSpeed;
unsigned m2_endSpeed;
unsigned m2_curRC = kInitRC;
#ifdef DEBUG
unsigned m2_latency = 0;
unsigned m2_lastCount = 0;
#endif
unsigned long m2_actClock = 1500000;
unsigned m2_startSpeed;
unsigned int m2_acc = kMotorAccDefault;
long m2_rampTime;
long m2_rampEndTime;
float m2_rampScl = (float)(kClockFreq / kPrescale) / kMotorAccDefault;
int m2_minSpeed = kMinSpeed;
unsigned char m2_stopFlag = 0;
int m2_src = 3; // source clock
static tc_waveform_opt_t waveform_opt[NUM_MOTORS] = {
{
.channel = TC0_CHANNEL, // Channel selection.
.bswtrg = TC_EVT_EFFECT_NOOP, // Software trigger effect on TIOB.
.beevt = TC_EVT_EFFECT_NOOP, // External event effect on TIOB.
.bcpc = TC_EVT_EFFECT_NOOP, // RC compare effect on TIOB.
.bcpb = TC_EVT_EFFECT_NOOP, // RB compare effect on TIOB.
.aswtrg = TC_EVT_EFFECT_NOOP, // Software trigger effect on TIOA.
.aeevt = TC_EVT_EFFECT_NOOP, // External event effect on TIOA.
.acpc = TC_EVT_EFFECT_CLEAR, // RC compare effect on TIOA: clear output.
.acpa = TC_EVT_EFFECT_SET, // RA compare effect on TIOA: set (possibilities are none, toggle, set and clear).
.wavsel = TC_WAVEFORM_SEL_UP_MODE_RC_TRIGGER, // Waveform selection: Up mode with automatic trigger on RC compare.
.enetrg = FALSE, // External event trigger enable.
.eevt = TC_EXT_EVENT_SEL_TIOB_INPUT, // External event selection.
.eevtedg = TC_SEL_NO_EDGE, // External event edge selection.
.cpcdis = FALSE, // Counter disable when RC compare.
.cpcstop = FALSE, // Counter clock stopped with RC compare.
.burst = TC_BURST_NOT_GATED, // Burst signal selection.
.clki = TC_CLOCK_RISING_EDGE, // Clock inversion.
.tcclks = TC_CLOCK_SOURCE_TC3 // Internal source clock 3, connected to fPBA / 8. (pg 522)
},{
.channel = TC1_CHANNEL, // Channel selection.
.bswtrg = TC_EVT_EFFECT_NOOP, // Software trigger effect on TIOB.
.beevt = TC_EVT_EFFECT_NOOP, // External event effect on TIOB.
.bcpc = TC_EVT_EFFECT_NOOP, // RC compare effect on TIOB.
.bcpb = TC_EVT_EFFECT_NOOP, // RB compare effect on TIOB.
.aswtrg = TC_EVT_EFFECT_NOOP, // Software trigger effect on TIOA.
.aeevt = TC_EVT_EFFECT_NOOP, // External event effect on TIOA.
.acpc = TC_EVT_EFFECT_CLEAR, // RC compare effect on TIOA: clear output.
.acpa = TC_EVT_EFFECT_SET, // RA compare effect on TIOA: set (possibilities are none, toggle, set and clear).
.wavsel = TC_WAVEFORM_SEL_UP_MODE_RC_TRIGGER, // Waveform selection: Up mode with automatic trigger on RC compare.
.enetrg = FALSE, // External event trigger enable.
.eevt = TC_EXT_EVENT_SEL_TIOB_INPUT, // External event selection.
.eevtedg = TC_SEL_NO_EDGE, // External event edge selection.
.cpcdis = FALSE, // Counter disable when RC compare.
.cpcstop = FALSE, // Counter clock stopped with RC compare.
.burst = TC_BURST_NOT_GATED, // Burst signal selection.
.clki = TC_CLOCK_RISING_EDGE, // Clock inversion.
.tcclks = TC_CLOCK_SOURCE_TC3 // Internal source clock 3, connected to fPBA / 8. (pg 522)
},{
.channel = TC2_CHANNEL, // Channel selection.
.bswtrg = TC_EVT_EFFECT_NOOP, // Software trigger effect on TIOB.
.beevt = TC_EVT_EFFECT_NOOP, // External event effect on TIOB.
.bcpc = TC_EVT_EFFECT_NOOP, // RC compare effect on TIOB.
.bcpb = TC_EVT_EFFECT_NOOP, // RB compare effect on TIOB.
.aswtrg = TC_EVT_EFFECT_NOOP, // Software trigger effect on TIOA.
.aeevt = TC_EVT_EFFECT_NOOP, // External event effect on TIOA.
.acpc = TC_EVT_EFFECT_CLEAR, // RC compare effect on TIOA: clear output.
.acpa = TC_EVT_EFFECT_SET, // RA compare effect on TIOA: set (possibilities are none, toggle, set and clear).
.wavsel = TC_WAVEFORM_SEL_UP_MODE_RC_TRIGGER, // Waveform selection: Up mode with automatic trigger on RC compare.
.enetrg = FALSE, // External event trigger enable.
.eevt = TC_EXT_EVENT_SEL_TIOB_INPUT, // External event selection.
.eevtedg = TC_SEL_NO_EDGE, // External event edge selection.
.cpcdis = FALSE, // Counter disable when RC compare.
.cpcstop = FALSE, // Counter clock stopped with RC compare.
.burst = TC_BURST_NOT_GATED, // Burst signal selection.
.clki = TC_CLOCK_RISING_EDGE, // Clock inversion.
.tcclks = TC_CLOCK_SOURCE_TC3 // Internal source clock 3, connected to fPBA / 8. (pg 522)
}};
//-----------------------------------------------------------------------------
/*! \brief timer interrupt for motor
*/
__attribute__((__interrupt__))
static void m0_irq(void)
{
static char in = 0;
// clear the interrupt flag by reading the TC status register
tc_read_sr(&AVR32_TC, TC0_CHANNEL);
#ifdef DEBUG
static unsigned long ticks = 0;
ticks++;
// toggle an LED to indicate we are running
if (! (ticks % (16*200))) gpio_tgl_gpio_pin(LED0_GPIO);
#endif
// keep track of motor position
if (m0_motorOn) {
if (m0_motorDir) {
--m0_motorPos;
} else {
++m0_motorPos;
}
}
// return now if already inside interrupt
if (in) return;
in = 1;
// re-enable interrupts so we don't miss a count
Enable_interrupt_level(0);
if (m0_stepMode && ((long)((m0_motorPos - m0_stepNext) * (1 - 2 * (long)m0_motorDir)) > -2)) {
switch (m0_stepMode) {
case 1: // ramp down in middle of ramping up
case 2: // ramp down from cruising
m0_stepMode = 3;
m0_stepNext = m0_stepTo;
m0_rampTo = 60000; // = m0_actClock / m0_minSpeed
m0_rampFlag = 2;
break;
case 3: // time to stop
m0_stepMode = 0;
m0_rampFlag = 3; // halt!
break;
}
}
if (m0_rampFlag) {
m0_stopFlag = m0_rampFlag;
m0_rampFlag = 0;
if (m0_rampTo != m0_curRC || m0_stopFlag >= 2) {
m0_curSpeed = (unsigned)(kClockFreq / (kPrescale * (long)m0_curRC));
m0_endSpeed = (unsigned)(kClockFreq / (kPrescale * (long)m0_rampTo));
m0_startSpeed = m0_curSpeed;
if (m0_stopFlag == 3) {
m0_rampEndTime = 0;
} else if (m0_startSpeed < m0_endSpeed) {
m0_rampEndTime = (long)(((int)m0_endSpeed - (int)m0_startSpeed) * m0_rampScl);
} else {
m0_rampEndTime = (long)(((int)m0_startSpeed - (int)m0_endSpeed) * m0_rampScl);
}
m0_rampTime = 0;
m0_ramping = 1;
#ifdef DEBUG
m0_latency = 0;
#endif
}
} else if (m0_ramping) {
m0_rampTime += m0_curRC;
if (m0_rampTime >= m0_rampEndTime) {
// stop TC if stopping motor
if (m0_stopFlag >= 2) {
if ((m0_stopFlag == 2) && m0_stepMode) {
// don't stop until we reach our end point
in = 0;
return;
}
tc_stop(&AVR32_TC, TC0_CHANNEL);
m0_curSpeed = kMinSpeed;
m0_running = 0;
m0_stepMode = 0;
} else {
m0_curSpeed = m0_endSpeed;
if (m0_stepMode) {
m0_stepMode = 2;
// next mode is when we have to start ramping down
m0_stepNext = m0_stepTo - (m0_motorPos - m0_stepFrom);
}
}
m0_ramping = 0;
} else {
// weird: things go funny if the last m0_startSpeed is cast to (int). why??
m0_curSpeed = (unsigned)((int)(((int)m0_endSpeed - (int)m0_startSpeed)
* (float)m0_rampTime / (float)m0_rampEndTime) + m0_startSpeed);
if (!m0_curSpeed) m0_curSpeed = 1;
}
m0_curRC = kClockFreq / (kPrescale * (unsigned long)m0_curSpeed);
// set RA/RC for new frequency
tc_write_ra(&AVR32_TC, TC0_CHANNEL, m0_curRC >> 1);
tc_write_rc(&AVR32_TC, TC0_CHANNEL, m0_curRC);
#ifdef DEBUG
unsigned int lat = tc_read_tc(&AVR32_TC, TC0_CHANNEL);
if (lat > m0_latency) m0_latency = lat;
#endif
}
#ifdef DEBUG
m0_lastCount = tc_read_tc(&AVR32_TC, TC0_CHANNEL);
#endif
in = 0;
}
//-----------------------------------------------------------------------------
/*! \brief timer interrupt for motor
*/
__attribute__((__interrupt__))
static void m1_irq(void)
{
static char in = 0;
// clear the interrupt flag by reading the TC status register
tc_read_sr(&AVR32_TC, TC1_CHANNEL);
#ifdef DEBUG
static unsigned long ticks = 0;
ticks++;
// toggle an LED to indicate we are running
if (! (ticks % (16*200))) gpio_tgl_gpio_pin(LED1_GPIO);
#endif
// keep track of motor position
if (m1_motorOn) {
if (m1_motorDir) {
--m1_motorPos;
} else {
++m1_motorPos;
}
}
// return now if already inside interrupt
if (in) return;
in = 1;
// re-enable interrupts so we don't miss a count
Enable_interrupt_level(0);
if (m1_rampFlag) {
m1_stopFlag = m1_rampFlag;
m1_rampFlag = 0;
if (m1_rampTo != m1_curRC || m1_stopFlag >= 2) {
m1_curSpeed = (unsigned)(kClockFreq / (kPrescale * (long)m1_curRC));
m1_endSpeed = (unsigned)(kClockFreq / (kPrescale * (long)m1_rampTo));
m1_startSpeed = m1_curSpeed;
if (m1_stopFlag == 3) {
m1_rampEndTime = 0;
} else if (m1_startSpeed < m1_endSpeed) {
m1_rampEndTime = (long)(((int)m1_endSpeed - (int)m1_startSpeed) * m1_rampScl);
} else {
m1_rampEndTime = (long)(((int)m1_startSpeed - (int)m1_endSpeed) * m1_rampScl);
}
m1_rampTime = 0;
m1_ramping = 1;
#ifdef DEBUG
m1_latency = 0;
#endif
}
} else if (m1_ramping) {
m1_rampTime += m1_curRC;
if (m1_rampTime >= m1_rampEndTime) {
// stop TC if stopping motor
if (m1_stopFlag >= 2) {
tc_stop(&AVR32_TC, TC1_CHANNEL);
m1_curSpeed = kMinSpeed;
m1_running = 0;
} else {
m1_curSpeed = m1_endSpeed;
}
m1_ramping = 0;
} else {
// weird: things go funny if the last m1_startSpeed is cast to (int). why??
m1_curSpeed = (unsigned)((int)(((int)m1_endSpeed - (int)m1_startSpeed)
* (float)m1_rampTime / (float)m1_rampEndTime) + m1_startSpeed);
if (!m1_curSpeed) m1_curSpeed = 1;
}
m1_curRC = kClockFreq / (kPrescale * (unsigned long)m1_curSpeed);
// set RA/RC for new frequency
tc_write_ra(&AVR32_TC, TC1_CHANNEL, m1_curRC >> 1);
tc_write_rc(&AVR32_TC, TC1_CHANNEL, m1_curRC);
#ifdef DEBUG
unsigned int lat = tc_read_tc(&AVR32_TC, TC1_CHANNEL);
if (lat > m1_latency) m1_latency = lat;
#endif
}
#ifdef DEBUG
m1_lastCount = tc_read_tc(&AVR32_TC, TC1_CHANNEL);
#endif
in = 0;
}
//-----------------------------------------------------------------------------
/*! \brief timer interrupt for motor
*/
__attribute__((__interrupt__))
static void m2_irq(void)
{
static char in = 0;
// clear the interrupt flag by reading the TC status register
tc_read_sr(&AVR32_TC, TC2_CHANNEL);
#ifdef DEBUG
static unsigned long ticks = 0;
ticks++;
// toggle an LED to indicate we are running
if (! (ticks % (16*200))) gpio_tgl_gpio_pin(LED2_GPIO);
#endif
// keep track of motor position
if (m2_motorOn) {
if (m2_motorDir) {
--m2_motorPos;
} else {
++m2_motorPos;
}
}
// return now if already inside interrupt
if (in) return;
in = 1;
// re-enable interrupts so we don't miss a count
Enable_interrupt_level(0);
if (m2_rampFlag) {
m2_stopFlag = m2_rampFlag;
m2_rampFlag = 0;
if (m2_rampTo != m2_curRC || m2_stopFlag >= 2) {
m2_curSpeed = (unsigned)(kClockFreq / (kPrescale * (long)m2_curRC));
m2_endSpeed = (unsigned)(kClockFreq / (kPrescale * (long)m2_rampTo));
m2_startSpeed = m2_curSpeed;
if (m2_stopFlag == 3) {
m2_rampEndTime = 0;
} else if (m2_startSpeed < m2_endSpeed) {
m2_rampEndTime = (long)(((int)m2_endSpeed - (int)m2_startSpeed) * m2_rampScl);
} else {
m2_rampEndTime = (long)(((int)m2_startSpeed - (int)m2_endSpeed) * m2_rampScl);
}
m2_rampTime = 0;
m2_ramping = 1;
#ifdef DEBUG
m2_latency = 0;
#endif
}
} else if (m2_ramping) {
m2_rampTime += m2_curRC;
if (m2_rampTime >= m2_rampEndTime) {
// stop TC if stopping motor
if (m2_stopFlag >= 2) {
tc_stop(&AVR32_TC, TC2_CHANNEL);
m2_curSpeed = kMinSpeed;
m2_running = 0;
} else {
m2_curSpeed = m2_endSpeed;
}
m2_ramping = 0;
} else {
// weird: things go funny if the last m2_startSpeed is cast to (int). why??
m2_curSpeed = (unsigned)((int)(((int)m2_endSpeed - (int)m2_startSpeed)
* (float)m2_rampTime / (float)m2_rampEndTime) + m2_startSpeed);
if (!m2_curSpeed) m2_curSpeed = 1;
}
m2_curRC = kClockFreq / (kPrescale * (unsigned long)m2_curSpeed);
// set RA/RC for new frequency
tc_write_ra(&AVR32_TC, TC2_CHANNEL, m2_curRC >> 1);
tc_write_rc(&AVR32_TC, TC2_CHANNEL, m2_curRC);
#ifdef DEBUG
unsigned int lat = tc_read_tc(&AVR32_TC, TC2_CHANNEL);
if (lat > m2_latency) m2_latency = lat;
#endif
}
#ifdef DEBUG
m2_lastCount = tc_read_tc(&AVR32_TC, TC2_CHANNEL);
#endif
in = 0;
}
//-----------------------------------------------------------------------------
void setPin(int n, int val)
{
if (output_mode[n] != 1) {
switch (output_mode[n]) {
case 3:
gpio_enable_gpio_pin(n);
// fall through!
case 2:
gpio_disable_pin_pull_up(n);
break;
}
output_mode[n] = 1;
}
if (val) {
gpio_set_gpio_pin(n);
} else {
gpio_clr_gpio_pin(n);
}
}
//-----------------------------------------------------------------------------
void resurfacer_task_init(void)
{
sof_cnt = 0;
data_length = 0;
has_data = 0;
// Don't need this - PH
//Usb_enable_sof_interrupt();
}
//-----------------------------------------------------------------------------
void usb_sof_action(void)
{
sof_cnt++;
}
//-----------------------------------------------------------------------------
// initialize the watchdog timer status LED
void wdt_init(void)
{
#if defined(MANIP) || defined(CUTE)
if (AVR32_PM.RCAUSE.wdt) {
setPin(LED3_GPIO, 0); // turn on LED3
}
#endif
wdt_disable();
}
//-----------------------------------------------------------------------------
// initialize the PWM output
// PWM channel initialization
//
#define PWM_CLK 187500 // PWM clock rate Hz (187500 = 12MHz / 64)
#define PWM_CHAN 6 // use PWM6
#define PWM_PIN AVR32_PWM_6_2_PIN
#define PWM_FN AVR32_PWM_6_2_FUNCTION
#define PWM_WID 2 // pulse width (clock ticks, must be less than kMinTop)
static pwm_opt_t pwm_opt = {
// PWM controller configuration.
.diva = AVR32_PWM_DIVA_CLK_OFF,
.divb = AVR32_PWM_DIVB_CLK_OFF,
.prea = AVR32_PWM_PREA_MCK,
.preb = AVR32_PWM_PREB_MCK
};
static avr32_pwm_channel_t pwm_channel = {
// .CMR.calg = PWM_MODE_LEFT_ALIGNED, // Channel mode.
// .CMR.cpol = PWM_POLARITY_LOW, // Channel polarity.
// .CMR.cpd = PWM_UPDATE_PERIOD, // Not used the first time.
// .CMR.cpre = AVR32_PWM_CPRE_MCK_DIV_64, // Channel prescaler.
.cdty = PWM_WID,// Channel duty cycle, should be < CPRD (2 --> 10 microsec)
.cprd = 20, // Channel period (set later)
.cupd = 0, // Channel update is not used here
.ccnt = 0
// With these settings, the output waveform rate will be : (12000000/64)/20
};
// run PWM at specified rate (0 = stop)
void pwm_spd(float rate)
{
// (i can't figure out how to initialize these in the variable definition)
pwm_channel.CMR.calg = PWM_MODE_LEFT_ALIGNED; // Channel mode.
pwm_channel.CMR.cpol = PWM_POLARITY_HIGH; // Channel polarity.
pwm_channel.CMR.cpd = PWM_UPDATE_PERIOD; // Not used the first time.
pwm_channel.CMR.cpre = AVR32_PWM_CPRE_MCK_DIV_64; // Channel prescaler.
if (rate) {
// initialize the PWM if necessary
if (!pwm_flag) {
pwm_init(&pwm_opt);
pwm_flag = 1; // (stopped)
}
// calculate PWM period
unsigned long rcl = (unsigned long)(PWM_CLK / rate);
if (rcl > 0xfffff) rcl = 0xfffff; // cprd is 20 bits
if (rcl < kMinTop) rcl = kMinTop;
pwm_channel.cprd = rcl;
if (pwm_flag == 1) { // stopped?
// init this channel and start the PWM
pwm_channel_init(PWM_CHAN, &pwm_channel);
// enable PWM function pin if necessary
if (output_mode[PWM_PIN] != 3) {
output_mode[PWM_PIN] = 3;
gpio_enable_module_pin(PWM_PIN, PWM_FN);
}
pwm_start_channels(1 << PWM_CHAN); // start pwm
pwm_flag = 2; // (running)
} else {
// already running, so just update the period
AVR32_PWM.channel[PWM_CHAN].cupd = rcl; // (will update period on the next cycle)
}
} else if (pwm_flag == 2) {
// drive the output pin low
gpio_clr_gpio_pin(PWM_PIN); // (set the pin low first to try to avoid a transient pulse)
gpio_enable_gpio_pin(PWM_PIN);
gpio_clr_gpio_pin(PWM_PIN); // (must clear pin again, since enable_gpio_pin apparently resets this)
output_mode[PWM_PIN] = 1;
// stop the PWM
pwm_stop_channels(1 << PWM_CHAN);
pwm_flag = 1; // (stopped)
}
}
//-----------------------------------------------------------------------------
// activate the watchdog timer
void wdt_scheduler(void)
{
// If Reset Cause is due to a Watchdog reset just relaunch Watchdog and turn
// on LED3 on to let user know that a new wdt reset has occured (MANIP/CUTE only).
if (AVR32_PM.RCAUSE.wdt) {
wdt_reenable();
wdt_flag = 2;
// If Reset Cause is due to a Power On or external reset...
// } else if (AVR32_PM.RCAUSE.por || AVR32_PM.RCAUSE.ext) {
} else {
// Save current value in GPLP register (preserved across reset)
// pm_write_gplp(&AVR32_PM,0,current_wdt_value);
// enable the watchdog timer
wdt_enable(current_wdt_value);
wdt_flag = 1;
}
}
// read comma-separated channels from string
// returns error string, or NULL on success
char *getValues(int *chan, char *str, int num, int max)
{
int i,j,n;
for (i=0,j=0,n=0; ; ++j) {
char ch = str[j];
if (ch == ',' || !ch) {
if (n >= max) return "value out of range";
if (i >= num) return "too many channels";
chan[i++] = n;
n = 0;
if (!ch) break;
} else if (ch >= '0' && ch <= '9') {
n = 10 * n + ch - '0';
} else {
return "invalid channel";
}
}
return NULL;
}
// delay loop
// (apparently there is are delay_ms() and delay_us() functions defined
// in delay.h that I could use instead of just looping here)
#if defined(MANIP) || defined(CUTE)
int delay(int del_num)
{
int i, n;
int dummy=0;
if (del_num < kNumDelay) {
n = cfg_del[del_num];
for (i=0; i<n; ++i) ++dummy;
}
return dummy;
}
#endif
//-----------------------------------------------------------------------------
// this is the task that handles incoming commands over USB, executes them, and sends a response
void resurfacer_task()
{
const int bsiz = 256;
int len, pos, i, j, n, n2;
char msg_buff[512];
char cmd_buff[bsiz];
static char out_buff[OUT_SIZE];
static char buf[EP_SIZE_TEMP2];
if (!Is_device_enumerated()) return; // Check if USB HID is enumerated
if (Is_usb_out_received(EP_TEMP_OUT)) {
// clear the watchdog timer because we are alive
if (!wdt_flag) {
wdt_scheduler(); // enable watchdog timer
} else {
wdt_clear();
}
Usb_reset_endpoint_fifo_access(EP_TEMP_OUT);
len = Usb_byte_count(EP_TEMP_OUT);
usb_read_ep_rxpacket(EP_TEMP_OUT, buf, len, NULL);
Usb_ack_out_received_free(EP_TEMP_OUT);
pos = 0;
for (;;) { // loop through commands
char *cmd = cmd_buff;
char *dat;
char *err = (char *)0;
char idx = '\0';
int ok = 0;
msg_buff[0] = '\0';
for (;;) { // (a cheap goto)
// read command
while (pos < len) {
char ch = buf[pos++];
if (ch == '\n' || ch == ';') break; // semicolon is command terminator
*(cmd++) = ch;
if (cmd - cmd_buff >= bsiz) { err = "cmd too big"; break; }
if (pos >= len) { err = "no cmd"; break; }
}
if (err) break;
*cmd = '\0';
// decode the command
cmd = strtok(cmd_buff, " ");
if (!cmd) { err = "no cmd"; break; }
dat = strtok(NULL, " ");
if (cmd[0] && (cmd[1] == '.')) {
idx = cmd[0];
cmd += 2; // skip index
} else {
idx = '\0';
}
if (cmd[0]=='m' && cmd[1]>='0' && cmd[1]-'0'<NUM_MOTORS && !cmd[2]) {
// Command: m# CMD - motor commands
int mot_num = cmd[1] - '0';
cmd = dat;