-
Notifications
You must be signed in to change notification settings - Fork 12
/
controller.c
executable file
·1142 lines (1039 loc) · 36.7 KB
/
controller.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
#include "controller.h"
#include "ch.h"
#include "hal.h"
#include "hw_conf.h"
#include "stm32f4xx_conf.h"
#include "isr_vector_table.h"
#include "comm_usb.h"
#include "encoder.h"
#include "transforms.h"
#include "zsm.h"
#include "datatypes.h"
#include "config.h"
#include <string.h>
#include <math.h>
#include "utils.h"
#include "console.h"
#include "scope.h"
#define SYSTEM_CORE_CLOCK 168000000
#define DEAD_TIME_CYCLES 60
#define SET_DUTY(duty1, duty2, duty3) \
TIM1->CR1 |= TIM_CR1_UDIS; \
TIM1->CCR1 = (int)(duty3 * TIM1->ARR); \
TIM1->CCR2 = (int)(duty2 * TIM1->ARR); \
TIM1->CCR3 = (int)(duty1 * TIM1->ARR); \
TIM1->CR1 &= ~TIM_CR1_UDIS;
#define SET_DUTY_CURRENT_SAMPLE(duty1, duty2, duty3, current_sample) \
TIM1->CR1 |= TIM_CR1_UDIS; \
TIM1->CCR1 = (int)(duty3 * TIM1->ARR); \
TIM1->CCR2 = (int)(duty2 * TIM1->ARR); \
TIM1->CCR3 = (int)(duty1 * TIM1->ARR); \
TIM1->CCR4 = current_sample; \
TIM1->CR1 &= ~TIM_CR1_UDIS;
#define DISABLE_PRELOAD_DUTY1() TIM1->CCMR2 &= (uint16_t)(~TIM_CCMR2_OC3PE)
#define DISABLE_PRELOAD_DUTY2() TIM1->CCMR1 &= (uint16_t)(~TIM_CCMR1_OC2PE)
#define DISABLE_PRELOAD_DUTY3() TIM1->CCMR1 &= (uint16_t)(~TIM_CCMR1_OC1PE)
#define ENABLE_PRELOAD_DUTY1() TIM1->CCMR2 |= (uint16_t)(TIM_CCMR2_OC3PE)
#define ENABLE_PRELOAD_DUTY2() TIM1->CCMR1 |= (uint16_t)(TIM_CCMR1_OC2PE)
#define ENABLE_PRELOAD_DUTY3() TIM1->CCMR1 |= (uint16_t)(TIM_CCMR1_OC1PE)
#define SET_PWM_FREQ(freq) \
TIM1->CR1 |= TIM_CR1_UDIS; \
if (freq < 100) \
{ \
TIM1->PSC = 31; \
TIM1->ARR = SYSTEM_CORE_CLOCK / 2 / (freq * 32); \
} \
else if (freq < 200) \
{ \
TIM1->PSC = 15; \
TIM1->ARR = SYSTEM_CORE_CLOCK / 2 / (freq * 16); \
} \
else if (freq < 400) \
{ \
TIM1->PSC = 7; \
TIM1->ARR = SYSTEM_CORE_CLOCK / 2 / (freq * 8); \
} \
else if (freq < 700) \
{ \
TIM1->PSC = 3; \
TIM1->ARR = SYSTEM_CORE_CLOCK / 2 / (freq * 4); \
} \
else if (freq < 1300) \
{ \
TIM1->PSC = 1; \
TIM1->ARR = SYSTEM_CORE_CLOCK / 2 / (freq * 2); \
} \
else \
{ \
TIM1->PSC = 0; \
TIM1->ARR = SYSTEM_CORE_CLOCK / 2 / freq; \
} \
TIM1->CCR4 = TIM1->ARR - 2; \
TIM1->CR1 &= ~TIM_CR1_UDIS;
#define CHECK_CURRENT(adc) (adc > 100 && adc < 4096 - 100)
typedef struct {
float edeg;
float edeg_obs;
float i_a;
float i_b;
float i_c;
float i_alpha;
float i_beta;
float i_d;
float i_q;
float i_bus;
float i_abs;
float v_a;
float v_b;
float v_c;
float v_a_norm;
float v_b_norm;
float v_c_norm;
float v_alpha;
float v_beta;
float v_alpha_norm;
float v_beta_norm;
float v_d;
float v_q;
float v_d_norm;
float v_q_norm;
float v_bus;
float integral_d;
float integral_q;
} motor_state_t;
static volatile Config *config;
static volatile ControllerState state = STOPPED;
static volatile ControllerFault fault = NO_FAULT;
static volatile ControllerMode mode = NONE;
static volatile uint16_t ADC_Value[3];
static volatile motor_state_t motor_state;
static volatile int adc1_1;
static volatile int adc2_1;
static volatile int adc3_1;
static volatile int adc1_2;
static volatile int adc2_2;
static volatile int adc3_2;
static volatile float temperature;
static volatile int e = 0;
static volatile float a, b, c;
static volatile float commandDutyCycle = 0.0;
static volatile float commandCurrentQ = 0.0;
static volatile float commandCurrentD = 0.0;
static volatile float commandSpeed = 0.0;
static volatile bool overrideAngle = false;
static volatile float angleToOverride;
static volatile bool pwmEnabled = false;
static volatile float pllAngle;
static volatile float pllSpeed;
static volatile float speedIntegral = 0.0;
static volatile float speedPrevError = 0.0;
static volatile float inductance_measure_duty = 0.0;
static volatile float faultValue = 0.0;
static volatile float observer_x1 = 0.0;
static volatile float observer_x2 = 0.0;
static volatile float looptime = 0.0;
static void apply_zsm(volatile float *a, volatile float *b, volatile float *c);
static void pll_run(float angle, float dt, volatile float *pll_angle,
volatile float *pll_speed);
static void observer_update(float v_alpha, float v_beta, float i_alpha, float i_beta,
float dt, volatile float *x1, volatile float *x2, volatile float *angle_obs);
static void disable_pwm(void);
static void enable_pwm(void);
static void play_startup_tone(void);
CH_IRQ_HANDLER(ADC1_2_3_IRQHandler) {
CH_IRQ_PROLOGUE();
chSysLockFromISR();
ADC_ClearITPendingBit(ADC1, ADC_IT_JEOC);
controller_update();
chSysUnlockFromISR();
CH_IRQ_EPILOGUE();
}
void controller_init(void)
{
config = config_get_configuration();
memset((void*)&motor_state, 0, sizeof(motor_state_t));
overrideAngle = false;
pwmEnabled = false;
pllAngle = 0.0;
pllSpeed = 0.0;
utils_sys_lock_cnt();
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
TIM_OCInitTypeDef TIM_OCInitStructure;
TIM_BDTRInitTypeDef TIM_BDTRInitStructure;
TIM_DeInit(TIM1);
TIM1->CNT = 0;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE);
// Time Base configuration
TIM_TimeBaseStructure.TIM_Prescaler = 0;
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_CenterAligned2; // compare flag when upcounting
TIM_TimeBaseStructure.TIM_Period = SYSTEM_CORE_CLOCK / 2 / config->pwmFrequency;
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
TIM_TimeBaseStructure.TIM_RepetitionCounter = 1; // Only generate update event on underflow
TIM_TimeBaseInit(TIM1, &TIM_TimeBaseStructure);
// Channel 1, 2 and 3 Configuration in PWM mode
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable;
TIM_OCInitStructure.TIM_Pulse = TIM1->ARR / 2;
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
TIM_OCInitStructure.TIM_OCNPolarity = TIM_OCNPolarity_High;
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Set;
TIM_OC1Init(TIM1, &TIM_OCInitStructure);
TIM_OC2Init(TIM1, &TIM_OCInitStructure);
TIM_OC3Init(TIM1, &TIM_OCInitStructure);
TIM_OC4Init(TIM1, &TIM_OCInitStructure);
TIM_OC1PreloadConfig(TIM1, TIM_OCPreload_Enable);
TIM_OC2PreloadConfig(TIM1, TIM_OCPreload_Enable);
TIM_OC3PreloadConfig(TIM1, TIM_OCPreload_Enable);
TIM_OC4PreloadConfig(TIM1, TIM_OCPreload_Enable);
// Automatic Output enable, Break, dead time and lock configuration
TIM_BDTRInitStructure.TIM_OSSRState = TIM_OSSRState_Enable;
TIM_BDTRInitStructure.TIM_OSSIState = TIM_OSSIState_Enable;
TIM_BDTRInitStructure.TIM_LOCKLevel = TIM_LOCKLevel_OFF;
TIM_BDTRInitStructure.TIM_DeadTime = DEAD_TIME_CYCLES;
TIM_BDTRInitStructure.TIM_Break = TIM_Break_Disable;
TIM_BDTRInitStructure.TIM_BreakPolarity = TIM_BreakPolarity_High;
TIM_BDTRInitStructure.TIM_AutomaticOutput = TIM_AutomaticOutput_Disable;
TIM_BDTRConfig(TIM1, &TIM_BDTRInitStructure);
TIM_CCPreloadControl(TIM1, ENABLE);
TIM_ARRPreloadConfig(TIM1, ENABLE);
ADC_CommonInitTypeDef ADC_CommonInitStructure;
DMA_InitTypeDef DMA_InitStructure;
ADC_InitTypeDef ADC_InitStructure;
// Clock
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA2, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1 | RCC_APB2Periph_ADC2 | RCC_APB2Periph_ADC3, ENABLE);
// DMA for the ADC
DMA_InitStructure.DMA_Channel = DMA_Channel_0;
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)&ADC_Value;
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&ADC->CDR;
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory;
DMA_InitStructure.DMA_BufferSize = 3;
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Disable;
DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull;
DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single;
DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
DMA_Init(DMA2_Stream4, &DMA_InitStructure);
// DMA2_Stream0 enable
DMA_Cmd(DMA2_Stream4, ENABLE);
// ADC Common Init
// Note that the ADC is running at 42MHz, which is higher than the
// specified 36MHz in the data sheet, but it works.
ADC_CommonInitStructure.ADC_Mode = ADC_TripleMode_InjecSimult;
ADC_CommonInitStructure.ADC_Prescaler = ADC_Prescaler_Div2;
ADC_CommonInitStructure.ADC_DMAAccessMode = ADC_DMAAccessMode_1;
ADC_CommonInitStructure.ADC_TwoSamplingDelay = ADC_TwoSamplingDelay_5Cycles;
ADC_CommonInit(&ADC_CommonInitStructure);
// Channel-specific settings
ADC_InitStructure.ADC_Resolution = ADC_Resolution_12b;
ADC_InitStructure.ADC_ScanConvMode = ENABLE;
ADC_InitStructure.ADC_ContinuousConvMode = DISABLE;
// ADC_InitStructure.ADC_ExternalTrigConvEdge = ADC_ExternalTrigConvEdge_Falling;
// ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_T1_CC4;
ADC_InitStructure.ADC_ExternalTrigConvEdge = ADC_ExternalTrigConvEdge_None;
ADC_InitStructure.ADC_ExternalTrigConv = 0;
ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
ADC_InitStructure.ADC_NbrOfConversion = 1;
ADC_Init(ADC1, &ADC_InitStructure);
ADC_Init(ADC2, &ADC_InitStructure);
ADC_Init(ADC3, &ADC_InitStructure);
// Enable Vrefint channel
// ADC_TempSensorVrefintCmd(ENABLE);
// Enable DMA request after last transfer (Multi-ADC mode)
ADC_MultiModeDMARequestAfterLastTransferCmd(ENABLE);
// Injected channels for current measurement at end of cycle
ADC_ExternalTrigInjectedConvConfig(ADC1, ADC_ExternalTrigInjecConv_T1_CC4);
// ADC_ExternalTrigInjectedConvConfig(ADC2, ADC_ExternalTrigInjecConv_T8_CC2);
ADC_ExternalTrigInjectedConvEdgeConfig(ADC1, ADC_ExternalTrigInjecConvEdge_Falling);
// ADC_ExternalTrigInjectedConvEdgeConfig(ADC2, ADC_ExternalTrigInjecConvEdge_Falling);
ADC_InjectedSequencerLengthConfig(ADC1, 3);
ADC_InjectedSequencerLengthConfig(ADC2, 3);
ADC_InjectedSequencerLengthConfig(ADC3, 2);
// ADC1 regular channels
ADC_InjectedChannelConfig(ADC1, CURR_A_CHANNEL, 1, ADC_SampleTime_15Cycles);
ADC_InjectedChannelConfig(ADC1, VSENSE_A_CHANNEL, 2, ADC_SampleTime_15Cycles);
ADC_InjectedChannelConfig(ADC1, VBUS_CHANNEL, 3, ADC_SampleTime_15Cycles);
// ADC_RegularChannelConfig(ADC1, ADC_Channel_Vrefint, 3, ADC_SampleTime_15Cycles);
// ADC2 regular channels
ADC_InjectedChannelConfig(ADC2, CURR_B_CHANNEL, 1, ADC_SampleTime_15Cycles);
ADC_InjectedChannelConfig(ADC2, VSENSE_B_CHANNEL, 2, ADC_SampleTime_15Cycles);
ADC_InjectedChannelConfig(ADC2, NTC_CHANNEL, 3, ADC_SampleTime_15Cycles);
// ADC3 regular channels
ADC_InjectedChannelConfig(ADC3, CURR_C_CHANNEL, 1, ADC_SampleTime_15Cycles);
ADC_InjectedChannelConfig(ADC3, VSENSE_C_CHANNEL, 2, ADC_SampleTime_15Cycles);
// Interrupt
ADC_ITConfig(ADC1, ADC_IT_JEOC, ENABLE);
nvicEnableVector(ADC_IRQn, 4);
// Enable ADC1
ADC_Cmd(ADC1, ENABLE);
// Enable ADC2
ADC_Cmd(ADC2, ENABLE);
// Enable ADC3
ADC_Cmd(ADC3, ENABLE);
TIM_Cmd(TIM1, ENABLE);
TIM_CtrlPWMOutputs(TIM1, ENABLE);
SET_DUTY_CURRENT_SAMPLE(0, 0, 0, TIM1->ARR - 2);
disable_pwm();
utils_sys_unlock_cnt();
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM12, ENABLE);
TIM_TimeBaseStructure.TIM_Period = 0xFFFFFFFF;
TIM_TimeBaseStructure.TIM_Prescaler = (uint16_t)(((SYSTEM_CORE_CLOCK / 2) / 10000000) - 1);
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
TIM_TimeBaseInit(TIM12, &TIM_TimeBaseStructure);
TIM_Cmd(TIM12, ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_WWDG, ENABLE);
WWDG_SetPrescaler(WWDG_Prescaler_1);
WWDG_SetWindowValue(255);
WWDG_Enable(100);
palSetPad(EN_GATE_GPIO, EN_GATE_PIN);
play_startup_tone();
scope_arm();
}
/* Updates the controller state machine. Called as an interrupt handler on new ADC sample. */
void controller_update(void)
{
TIM12->CNT = 0;
WWDG_SetCounter(100);
adc1_1 = ADC_GetInjectedConversionValue(ADC1, ADC_InjectedChannel_1);
adc2_1 = ADC_GetInjectedConversionValue(ADC2, ADC_InjectedChannel_1);
adc3_1 = ADC_GetInjectedConversionValue(ADC3, ADC_InjectedChannel_1);
adc1_2 = ADC_GetInjectedConversionValue(ADC1, ADC_InjectedChannel_2);
adc2_2 = ADC_GetInjectedConversionValue(ADC2, ADC_InjectedChannel_2);
adc3_2 = ADC_GetInjectedConversionValue(ADC3, ADC_InjectedChannel_2);
int adc1_3 = ADC_GetInjectedConversionValue(ADC1, ADC_InjectedChannel_3);
int adc2_3 = ADC_GetInjectedConversionValue(ADC2, ADC_InjectedChannel_3);
temperature = adc2_3;
motor_state.v_bus = adc1_3 * (V_REG / 4095.0) * (VBUS_R1 + VBUS_R2) / VBUS_R2;
motor_state.i_a = ((int16_t)adc1_1 - 2048) * (V_REG / 4095.0) / (CURRENT_SENSE_RES * CURRENT_AMP_GAIN);
motor_state.i_b = ((int16_t)adc2_1 - 2048) * (V_REG / 4095.0) / (CURRENT_SENSE_RES * CURRENT_AMP_GAIN);
motor_state.i_c = ((int16_t)adc3_1 - 2048) * (V_REG / 4095.0) / (CURRENT_SENSE_RES * CURRENT_AMP_GAIN);
if (fault == OVERCURRENT || !(CHECK_CURRENT(adc1_1) && CHECK_CURRENT(adc2_1) && CHECK_CURRENT(adc3_1)))
{
disable_pwm();
SET_DUTY(0, 0, 0);
palClearPad(EN_GATE_GPIO, EN_GATE_PIN);
fault = OVERCURRENT;
state = STOPPED;
if (!CHECK_CURRENT(adc1_1))
faultValue = motor_state.i_a;
if (!CHECK_CURRENT(adc2_1))
faultValue = motor_state.i_b;
if (!CHECK_CURRENT(adc3_1))
faultValue = motor_state.i_c;
return;
}
// Check for ADC measurements that happened when the low side PWM was too short
if (motor_state.v_a_norm > 0.95)
{
motor_state.i_a = -(motor_state.i_b + motor_state.i_c);
}
else if (motor_state.v_b_norm > 0.95)
{
motor_state.i_b = -(motor_state.i_a + motor_state.i_c);
}
else if (motor_state.v_c_norm > 0.95)
{
motor_state.i_c = -(motor_state.i_a + motor_state.i_b);
}
// If all are good, use all the balanced current assumption to use all three channels to improve each channel's measurement
else if (motor_state.v_a_norm <= 0.95 && motor_state.v_b_norm <= 0.95 && motor_state.v_c_norm <= 0.95)
{
motor_state.i_a = motor_state.i_a / 2.0 - (motor_state.i_b + motor_state.i_c) / 2.0;
motor_state.i_b = motor_state.i_b / 2.0 - (motor_state.i_a + motor_state.i_c) / 2.0;
motor_state.i_c = motor_state.i_c / 2.0 - (motor_state.i_a + motor_state.i_b) / 2.0;
}
const float dt = 1.0 / config->pwmFrequency;
transforms_clarke(motor_state.i_a, motor_state.i_b, motor_state.i_c, &motor_state.i_alpha, &motor_state.i_beta);
transforms_park(motor_state.i_alpha, motor_state.i_beta, motor_state.edeg, &motor_state.i_d, &motor_state.i_q);
/*observer_update(motor_state.v_alpha, motor_state.v_beta,*/
/*motor_state.i_alpha, motor_state.i_beta, dt,*/
/*&observer_x1, &observer_x2, &motor_state.edeg_obs);*/
uint32_t inductance_duty = (uint32_t)((float)TIM1->ARR * inductance_measure_duty);
static uint8_t inductance_cnt = 0;
switch(state)
{
case STOPPED:
motor_state.edeg = encoder_get_angle();
SET_DUTY(0, 0, 0);
break;
case RUNNING:
motor_state.edeg = encoder_get_angle();
if (overrideAngle)
{
motor_state.edeg = angleToOverride;
}
if (mode == SPEED)
{
float p_term;
float d_term;
// Too low RPM set. Reset state and return.
/*if (fabsf(m_speed_pid_set_rpm) < m_conf->s_pid_min_erpm) {*/
/*i_term = 0.0;*/
/*prev_error = 0;*/
/*return;*/
/*}*/
float scale = 1.0 / motor_state.v_bus;
float error = commandSpeed - controller_get_erpm();
p_term = error * config->speedKp * scale;
speedIntegral += error * (config->speedKi * dt) * scale;
d_term = (error - speedPrevError) * (config->speedKd / dt) * scale;
if (speedIntegral > 1.0)
{
speedIntegral = 1.0;
}
else if (speedIntegral < -1.0)
{
speedIntegral = -1.0;
}
speedPrevError = error;
float output = p_term + speedIntegral + d_term;
if (output > 1.0)
{
output = 1.0;
}
else if (output < -1.0)
{
output = -1.0;
}
commandCurrentQ = output * config->maxCurrent;
}
else
{
speedIntegral = 0.0;
speedPrevError = 0.0;
}
float i_d_set = commandCurrentD;
float i_q_set = commandCurrentQ;
float i_d_err = i_d_set - motor_state.i_d;
float i_q_err = i_q_set - motor_state.i_q;
motor_state.integral_d += i_d_err * config->currentKi * dt;
motor_state.integral_q += i_q_err * config->currentKi * dt;
utils_saturate_vector_2d((float*)&motor_state.integral_d, (float*)&motor_state.integral_q,
(2.0 / 3.0) * config->maxDuty * SQRT3_BY_2 * motor_state.v_bus);
// TODO: Add back-EMF as feed forward term
motor_state.v_d = motor_state.integral_d + i_d_err * config->currentKp;
motor_state.v_q = motor_state.integral_q + i_q_err * config->currentKp;
motor_state.v_d_norm = motor_state.v_d / ((2.0 / 3.0) * motor_state.v_bus);
motor_state.v_q_norm = motor_state.v_q / ((2.0 / 3.0) * motor_state.v_bus);
utils_saturate_vector_2d((float*)&motor_state.v_d_norm, (float*)&motor_state.v_q_norm,
SQRT3_BY_2 * config->maxDuty);
transforms_inverse_park(motor_state.v_d_norm, motor_state.v_q_norm, motor_state.edeg, &motor_state.v_alpha_norm, &motor_state.v_beta_norm);
transforms_inverse_clarke(motor_state.v_alpha_norm, motor_state.v_beta_norm, &motor_state.v_a_norm, &motor_state.v_b_norm, &motor_state.v_c_norm);
apply_zsm(&motor_state.v_a_norm, &motor_state.v_b_norm, &motor_state.v_c_norm);
SET_DUTY(motor_state.v_a_norm, motor_state.v_b_norm, motor_state.v_c_norm);
/*scope_log(0, motor_state.edeg);*/
/*scope_log(1, motor_state.edeg_obs);*/
/*if (motor_state.i_q > 20.0 || motor_state.i_q < -20.0 || motor_state.i_d > 20.0 || motor_state.i_d < -20.0)*/
/*{*/
/*scope_trigger();*/
/*}*/
break;
case TONE:
SET_DUTY(0.005, 0, 0);
break;
case INDUCTANCE_MEASURE:
if (inductance_cnt == 0)
{
SET_DUTY_CURRENT_SAMPLE(0, 0, 0, inductance_duty - 10);
enable_pwm();
}
else if (inductance_cnt == 2)
{
SET_DUTY(0, inductance_measure_duty, inductance_measure_duty); // Current flows from B and C into A
}
else if (inductance_cnt == 3)
{
scope_log(0, -motor_state.i_a);
scope_log(1, motor_state.v_bus);
DISABLE_PRELOAD_DUTY2();
SET_DUTY(0, 0, 0);
ENABLE_PRELOAD_DUTY2();
}
else if (inductance_cnt == 5)
{
SET_DUTY(inductance_measure_duty, 0, inductance_measure_duty);
}
else if (inductance_cnt == 6)
{
scope_log(0, -motor_state.i_b);
scope_log(1, motor_state.v_bus);
DISABLE_PRELOAD_DUTY3();
SET_DUTY(0, 0, 0);
ENABLE_PRELOAD_DUTY3();
}
else if (inductance_cnt == 8)
{
SET_DUTY(inductance_measure_duty, inductance_measure_duty, 0);
}
else if (inductance_cnt == 9)
{
scope_log(0, -motor_state.i_c);
scope_log(1, motor_state.v_bus);
inductance_cnt = 0;
disable_pwm();
state = STOPPED;
SET_DUTY_CURRENT_SAMPLE(0, 0, 0, TIM1->ARR - 2);
break;
}
inductance_cnt++;
break;
}
pll_run(motor_state.edeg, dt, &pllAngle, &pllSpeed);
looptime = (float) TIM12->CNT / 10000000.0;
}
static void observer_update(float v_alpha, float v_beta, float i_alpha, float i_beta, float dt, volatile float *x1, volatile float *x2, volatile float *angle_obs)
{
const float L = (3.0 / 2.0) * config->motorInductance;
const float R = (3.0 / 2.0) * config->motorResistance;
const float gamma = config->observerGain;
const float linkage = config->motorFluxLinkage;
const float Lia = L * i_alpha;
const float Lib = L * i_beta;
float k1 = (linkage * linkage) - ((*x1 - Lia) * (*x1 - Lia) + (*x2 - Lib) * (*x2 - Lib));
float x1_dot = 0.0;
float x2_dot = 0.0;
x1_dot = -R * i_alpha + v_alpha + ((gamma / 2.0) * (*x1 - Lia)) * k1;
x2_dot = -R * i_beta + v_beta + ((gamma / 2.0) * (*x2 - Lib)) * k1;
*x1 += x1_dot * dt;
*x2 += x2_dot * dt;
if (fabsf(*x1) > 1e20 || (*x1 != *x1)) {
*x1 = 0.0;
}
if (fabsf(*x2) > 1e20 || (*x2 != *x2)) {
*x2 = 0.0;
}
*angle_obs = utils_atan2(*x2 - L * i_beta, *x1 - L * i_alpha) * 180.0 / M_PI;
if (*angle_obs < 0)
*angle_obs += 360.0;
}
void controller_set_duty(float duty)
{
if (duty > 1.0)
{
duty = 1.0;
}
else if (duty < -1.0)
{
duty = -1.0;
}
commandDutyCycle = duty;
state = RUNNING;
mode = DUTY_CYCLE;
if (!pwmEnabled)
enable_pwm();
}
void controller_set_current(float current)
{
if (current > config->maxCurrent)
{
current = config->maxCurrent;
}
else if (current < -config->maxCurrent)
{
current = -config->maxCurrent;
}
commandCurrentQ = current;
commandCurrentD = 0.0;
state = RUNNING;
mode = CURRENT;
if (!pwmEnabled)
enable_pwm();
}
void controller_set_speed(float speed)
{
commandSpeed = speed;
state = RUNNING;
mode = SPEED;
if (!pwmEnabled)
enable_pwm();
}
void controller_disable(void)
{
state = STOPPED;
mode = NONE;
motor_state.integral_d = 0.0;
motor_state.integral_q = 0.0;
commandCurrentQ = 0.0;
commandCurrentD = 0.0;
commandSpeed = 0.0;
commandDutyCycle = 0.0;
if (pwmEnabled)
disable_pwm();
}
float controller_get_bus_voltage(void)
{
return motor_state.v_bus;
}
float controller_get_temperature(void)
{
return (1.0 / ((logf(((4095.0 * 10000.0) / temperature - 10000.0) / 10000.0) / 3434.0) + (1.0 / 298.15)) - 273.15);
}
bool controller_encoder_zero(float current, float *zero, bool *inverted)
{
overrideAngle = true;
angleToOverride = 0.0;
commandCurrentQ = 0.0;
commandCurrentD = current;
state = RUNNING;
if (!pwmEnabled)
enable_pwm();
chThdSleepMilliseconds(800);
*zero = encoder_get_raw_angle();
commandCurrentD = current / 2.0;
float i = 0;
float deg = *zero;
int incCount = 0;
for (i = 1.0; i <= 180.0; i++)
{
angleToOverride = i;
chThdSleepMilliseconds(1);
float temp = encoder_get_raw_angle();
if (temp > deg)
{
incCount++;
}
else if (temp < deg)
{
incCount--;
}
deg = temp;
}
if (incCount == 0)
{
return false;
}
*inverted = incCount < 0;
commandCurrentQ = commandCurrentD = 0.0;
overrideAngle = false;
controller_disable();
return true;
}
float controller_measure_resistance(float current, uint16_t samples)
{
overrideAngle = true;
angleToOverride = 0.0;
commandCurrentQ = current;
commandCurrentD = 0.0;
const float pwmFreqOld = config->pwmFrequency;
const float currentKpOld = config->currentKp;
const float currentKiOld = config->currentKi;
config->pwmFrequency = 10000.0;
config->currentKp = 0.01;
config->currentKi = 10.0;
SET_PWM_FREQ(config->pwmFrequency);
state = RUNNING;
if (!pwmEnabled)
enable_pwm();
chThdSleepMilliseconds(1000);
float current_sum = 0;
float voltage_sum = 0;
uint16_t i = 0;
for (i = 0; i < samples; i++)
{
const volatile float vd = motor_state.v_d;
const volatile float vq = motor_state.v_q;
const volatile float id = motor_state.i_d;
const volatile float iq = motor_state.i_q;
current_sum += sqrtf(id * id + iq * iq);
voltage_sum += sqrtf(vd * vd + vq * vq);
chThdSleepMilliseconds(1);
}
commandCurrentQ = commandCurrentD = 0.0;
overrideAngle = false;
controller_disable();
config->pwmFrequency = pwmFreqOld;
config->currentKp = currentKpOld;
config->currentKi = currentKiOld;
SET_PWM_FREQ(config->pwmFrequency);
float current_avg = current_sum / samples;
float voltage_avg = voltage_sum / samples;
return (voltage_avg / current_avg) * (2.0 / 3.0);
}
float controller_measure_inductance(float duty, uint16_t samples, float *curr)
{
const float pwmFreqOld = config->pwmFrequency;
config->pwmFrequency = 1500.0;
SET_PWM_FREQ(config->pwmFrequency);
scope_clear(0);
scope_clear(1);
scope_arm();
scope_trigger();
inductance_measure_duty = duty;
for (uint16_t i = 0; i < samples; i++)
{
state = INDUCTANCE_MEASURE;
while (state == INDUCTANCE_MEASURE)
{
chThdSleepMilliseconds(1);
}
}
float avg_current = scope_get_triggered_average(0);
float avg_voltage = scope_get_triggered_average(1);
float t = (float)TIM1->ARR * inductance_measure_duty / (float)SYSTEM_CORE_CLOCK -
(float)(10 + 50) / (float)SYSTEM_CORE_CLOCK;
if (curr != NULL)
{
*curr = avg_current;
}
config->pwmFrequency = pwmFreqOld;
SET_PWM_FREQ(config->pwmFrequency);
return ((avg_voltage * t) / avg_current) * 1e6 * (2.0 / 3.0);
}
float controller_get_observer_angle(void)
{
return motor_state.edeg_obs;
}
float controller_get_encoder_angle(void)
{
return motor_state.edeg;
}
float controller_get_erpm(void)
{
return pllSpeed / ((2.0 * M_PI) / 60.0);
}
float controller_get_current_q(void)
{
return motor_state.i_q;
}
float controller_get_current_d(void)
{
return motor_state.i_d;
}
float controller_get_looptime(void)
{
return looptime;
}
void controller_print(void)
{
/*USB_PRINT("%f, %f, %f, %f, %d, %d, %d, %f, %f, %f, %f, %f, %f, %f\n", motor_state.edeg, motor_state.v_a_norm, motor_state.v_b_norm, motor_state.v_c_norm, adc1_1, adc2_1, adc3_1, motor_state.i_a, motor_state.i_b, motor_state.i_c, motor_state.i_d, motor_state.i_q, motor_state.v_d, motor_state.v_q);*/
USB_PRINT("%f, %f, %f, %d\n", controller_get_erpm(), commandCurrentQ, commandSpeed, mode);
}
static void pll_run(float angle, float dt, volatile float *pll_angle,
volatile float *pll_speed) {
angle *= M_PI / 180.0;
float delta_theta = angle - *pll_angle;
utils_norm_angle_rad(&delta_theta);
*pll_angle += (*pll_speed + config->pllKp * delta_theta) * dt;
utils_norm_angle_rad((float*)pll_angle);
*pll_speed += config->pllKi * delta_theta * dt;
}
static void apply_zsm(volatile float *a, volatile float *b, volatile float *c)
{
switch(config->zsmMode)
{
case SINUSOIDAL:
zsm_sinusoidal(a, b, c);
break;
case MIDPOINT_CLAMP:
zsm_midpoint_clamp(a, b, c);
break;
case TOP_CLAMP:
zsm_top_clamp(a, b, c);
break;
case BOTTOM_CLAMP:
zsm_bottom_clamp(a, b, c);
break;
case TOP_BOTTOM_CLAMP:
zsm_top_clamp(a, b, c);
break;
}
}
static void disable_pwm(void)
{
SET_DUTY(0, 0, 0);
TIM_SelectOCxM(TIM1, TIM_Channel_1, TIM_ForcedAction_InActive);
TIM_CCxCmd(TIM1, TIM_Channel_1, TIM_CCx_Enable);
TIM_CCxNCmd(TIM1, TIM_Channel_1, TIM_CCxN_Disable);
TIM_SelectOCxM(TIM1, TIM_Channel_2, TIM_ForcedAction_InActive);
TIM_CCxCmd(TIM1, TIM_Channel_2, TIM_CCx_Enable);
TIM_CCxNCmd(TIM1, TIM_Channel_2, TIM_CCxN_Disable);
TIM_SelectOCxM(TIM1, TIM_Channel_3, TIM_ForcedAction_InActive);
TIM_CCxCmd(TIM1, TIM_Channel_3, TIM_CCx_Enable);
TIM_CCxNCmd(TIM1, TIM_Channel_3, TIM_CCxN_Disable);
TIM_GenerateEvent(TIM1, TIM_EventSource_COM);
pwmEnabled = false;
}
static void enable_pwm(void)
{
TIM_SelectOCxM(TIM1, TIM_Channel_1, TIM_OCMode_PWM1);
TIM_CCxCmd(TIM1, TIM_Channel_1, TIM_CCx_Enable);
TIM_CCxNCmd(TIM1, TIM_Channel_1, TIM_CCxN_Enable);
TIM_SelectOCxM(TIM1, TIM_Channel_2, TIM_OCMode_PWM1);
TIM_CCxCmd(TIM1, TIM_Channel_2, TIM_CCx_Enable);
TIM_CCxNCmd(TIM1, TIM_Channel_2, TIM_CCxN_Enable);
TIM_SelectOCxM(TIM1, TIM_Channel_3, TIM_OCMode_PWM1);
TIM_CCxCmd(TIM1, TIM_Channel_3, TIM_CCx_Enable);
TIM_CCxNCmd(TIM1, TIM_Channel_3, TIM_CCxN_Enable);
TIM_GenerateEvent(TIM1, TIM_EventSource_COM);
pwmEnabled = true;
}
ControllerFault controller_get_fault(void)
{
return fault;
}
float controller_get_fault_value(void)
{
return faultValue;
}
ControllerState controller_get_state(void)
{
return state;
}
float controller_get_command_current(void)
{
return commandCurrentQ;
}
typedef enum
{
NOTE_C0 = 0,
NOTE_CS0,
NOTE_D0,
NOTE_DS0,
NOTE_E0,
NOTE_F0,
NOTE_FS0,
NOTE_G0,
NOTE_GS0,
NOTE_A0,
NOTE_AS0,
NOTE_B0,
NOTE_C1,
NOTE_CS1,
NOTE_D1,
NOTE_DS1,
NOTE_E1,
NOTE_F1,
NOTE_FS1,
NOTE_G1,
NOTE_GS1,
NOTE_A1,
NOTE_AS1,
NOTE_B1,
NOTE_C2,
NOTE_CS2,
NOTE_D2,
NOTE_DS2,
NOTE_E2,
NOTE_F2,
NOTE_FS2,
NOTE_G2,
NOTE_GS2,
NOTE_A2,
NOTE_AS2,
NOTE_B2,
NOTE_C3,
NOTE_CS3,
NOTE_D3,
NOTE_DS3,
NOTE_E3,
NOTE_F3,
NOTE_FS3,
NOTE_G3,
NOTE_GS3,
NOTE_A3,
NOTE_AS3,
NOTE_B3,
NOTE_C4,
NOTE_CS4,
NOTE_D4,
NOTE_DS4,
NOTE_E4,
NOTE_F4,
NOTE_FS4,
NOTE_G4,
NOTE_GS4,
NOTE_A4,
NOTE_AS4,
NOTE_B4,
NOTE_C5,
NOTE_CS5,
NOTE_D5,
NOTE_DS5,
NOTE_E5,
NOTE_F5,
NOTE_FS5,
NOTE_G5,
NOTE_GS5,
NOTE_A5,
NOTE_AS5,
NOTE_B5,
NOTE_C6,
NOTE_CS6,
NOTE_D6,
NOTE_DS6,
NOTE_E6,
NOTE_F6,
NOTE_FS6,
NOTE_G6,
NOTE_GS6,
NOTE_A6,
NOTE_AS6,
NOTE_B6,
NOTE_C7,
NOTE_CS7,
NOTE_D7,
NOTE_DS7,
NOTE_E7,
NOTE_F7,
NOTE_FS7,
NOTE_G7,
NOTE_GS7,
NOTE_A7,
NOTE_AS7,
NOTE_B7,
NOTE_C8,
NOTE_CS8,
NOTE_D8,
NOTE_DS8,
NOTE_E8,
NOTE_F8,
NOTE_FS8,
NOTE_G8,
NOTE_GS8,
NOTE_A8,
NOTE_AS8,
NOTE_B8,