forked from variESC/bldc
-
Notifications
You must be signed in to change notification settings - Fork 0
/
mcpwm.c
3008 lines (2577 loc) · 81.2 KB
/
mcpwm.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
/*
Copyright 2016 Benjamin Vedder benjamin@vedder.se
This file is part of the VESC firmware.
The VESC firmware is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
The VESC firmware is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "ch.h"
#include "hal.h"
#include "stm32f4xx_conf.h"
#include <stdlib.h>
#include <math.h>
#include <stdio.h>
#include <string.h>
#include "mcpwm.h"
#include "mc_interface.h"
#include "digital_filter.h"
#include "utils.h"
#include "ledpwm.h"
#include "terminal.h"
#include "timeout.h"
#include "encoder.h"
#include "timer.h"
// Structs
typedef struct {
volatile bool updated;
volatile unsigned int top;
volatile unsigned int duty;
volatile unsigned int val_sample;
volatile unsigned int curr1_sample;
volatile unsigned int curr2_sample;
#ifdef HW_HAS_3_SHUNTS
volatile unsigned int curr3_sample;
#endif
} mc_timer_struct;
// Private variables
static volatile int comm_step; // Range [1 6]
static volatile int detect_step; // Range [0 5]
static volatile int direction;
static volatile float dutycycle_set;
static volatile float dutycycle_now;
static volatile float rpm_now;
static volatile float speed_pid_set_rpm;
static volatile float pos_pid_set_pos;
static volatile float current_set;
static volatile int tachometer;
static volatile int tachometer_abs;
static volatile int tachometer_for_direction;
static volatile int curr0_sum;
static volatile int curr1_sum;
static volatile int curr_start_samples;
static volatile int curr0_offset;
static volatile int curr1_offset;
static volatile mc_state state;
static volatile mc_control_mode control_mode;
static volatile float last_current_sample;
static volatile float last_current_sample_filtered;
static volatile float mcpwm_detect_currents_avg[6];
static volatile float mcpwm_detect_avg_samples[6];
static volatile float switching_frequency_now;
static volatile int ignore_iterations;
static volatile mc_timer_struct timer_struct;
static volatile int curr_samp_volt; // Use the voltage-synchronized samples for this current sample
static int hall_to_phase_table[16];
static volatile unsigned int slow_ramping_cycles;
static volatile int has_commutated;
static volatile mc_rpm_dep_struct rpm_dep;
static volatile float cycle_integrator_sum;
static volatile float cycle_integrator_iterations;
static volatile mc_configuration *conf;
static volatile float pwm_cycles_sum;
static volatile int pwm_cycles;
static volatile float last_pwm_cycles_sum;
static volatile float last_pwm_cycles_sums[6];
static volatile bool dccal_done;
static volatile bool sensorless_now;
static volatile int hall_detect_table[8][7];
static volatile bool init_done = false;
static volatile mc_comm_mode comm_mode_next;
static volatile float m_pll_phase;
static volatile float m_pll_speed;
static volatile uint32_t rpm_timer_start;
#ifdef HW_HAS_3_SHUNTS
static volatile int curr2_sum;
static volatile int curr2_offset;
#endif
// KV FIR filter
#define KV_FIR_TAPS_BITS 7
#define KV_FIR_LEN (1 << KV_FIR_TAPS_BITS)
#define KV_FIR_FCUT 0.02
static volatile float kv_fir_coeffs[KV_FIR_LEN];
static volatile float kv_fir_samples[KV_FIR_LEN];
static volatile int kv_fir_index = 0;
// Amplitude FIR filter
#define AMP_FIR_TAPS_BITS 7
#define AMP_FIR_LEN (1 << AMP_FIR_TAPS_BITS)
#define AMP_FIR_FCUT 0.02
static volatile float amp_fir_coeffs[AMP_FIR_LEN];
static volatile float amp_fir_samples[AMP_FIR_LEN];
static volatile int amp_fir_index = 0;
// Current FIR filter
#define CURR_FIR_TAPS_BITS 4
#define CURR_FIR_LEN (1 << CURR_FIR_TAPS_BITS)
#define CURR_FIR_FCUT 0.15
static volatile float current_fir_coeffs[CURR_FIR_LEN];
static volatile float current_fir_samples[CURR_FIR_LEN];
static volatile int current_fir_index = 0;
static volatile float last_adc_isr_duration;
static volatile float last_inj_adc_isr_duration;
// Global variables
volatile float mcpwm_detect_currents[6];
volatile float mcpwm_detect_voltages[6];
volatile float mcpwm_detect_currents_diff[6];
volatile int mcpwm_vzero;
// Private functions
static void set_duty_cycle_hl(float dutyCycle);
static void set_duty_cycle_ll(float dutyCycle);
static void set_duty_cycle_hw(float dutyCycle);
static void stop_pwm_ll(void);
static void stop_pwm_hw(void);
static void full_brake_ll(void);
static void full_brake_hw(void);
static void run_pid_control_speed(void);
static void run_pid_control_pos(float dt, float pos_now);
static void set_next_comm_step(int next_step);
static void update_rpm_tacho(void);
static void update_sensor_mode(void);
static int read_hall(void);
static void update_adc_sample_pos(mc_timer_struct *timer_tmp);
static void commutate(int steps);
static void set_next_timer_settings(mc_timer_struct *settings);
static void update_timer_attempt(void);
static void set_switching_frequency(float frequency);
static void do_dc_cal(void);
static void pll_run(float phase, float dt, volatile float *phase_var,
volatile float *speed_var);
// Defines
#define IS_DETECTING() (state == MC_STATE_DETECTING)
// Threads
static THD_WORKING_AREA(timer_thread_wa, 2048);
static THD_FUNCTION(timer_thread, arg);
static THD_WORKING_AREA(rpm_thread_wa, 1024);
static THD_FUNCTION(rpm_thread, arg);
static volatile bool timer_thd_stop;
static volatile bool rpm_thd_stop;
void mcpwm_init(volatile mc_configuration *configuration) {
utils_sys_lock_cnt();
init_done= false;
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
TIM_OCInitTypeDef TIM_OCInitStructure;
TIM_BDTRInitTypeDef TIM_BDTRInitStructure;
conf = configuration;
// Initialize variables
comm_step = 1;
detect_step = 0;
direction = 1;
rpm_now = 0.0;
dutycycle_set = 0.0;
dutycycle_now = 0.0;
speed_pid_set_rpm = 0.0;
pos_pid_set_pos = 0.0;
current_set = 0.0;
tachometer = 0;
tachometer_abs = 0;
tachometer_for_direction = 0;
state = MC_STATE_OFF;
control_mode = CONTROL_MODE_NONE;
last_current_sample = 0.0;
last_current_sample_filtered = 0.0;
switching_frequency_now = conf->m_bldc_f_sw_max;
ignore_iterations = 0;
curr_samp_volt = 0;
slow_ramping_cycles = 0;
has_commutated = 0;
memset((void*)&rpm_dep, 0, sizeof(rpm_dep));
cycle_integrator_sum = 0.0;
cycle_integrator_iterations = 0.0;
pwm_cycles_sum = 0.0;
pwm_cycles = 0;
last_pwm_cycles_sum = 0.0;
memset((float*)last_pwm_cycles_sums, 0, sizeof(last_pwm_cycles_sums));
dccal_done = false;
memset((void*)hall_detect_table, 0, sizeof(hall_detect_table[0][0]) * 8 * 7);
update_sensor_mode();
comm_mode_next = conf->comm_mode;
m_pll_phase = 0.0;
m_pll_speed = 0.0;
rpm_timer_start = 0;
mcpwm_init_hall_table((int8_t*)conf->hall_table);
// Create KV FIR filter
filter_create_fir_lowpass((float*)kv_fir_coeffs, KV_FIR_FCUT, KV_FIR_TAPS_BITS, 1);
// Create amplitude FIR filter
filter_create_fir_lowpass((float*)amp_fir_coeffs, AMP_FIR_FCUT, AMP_FIR_TAPS_BITS, 1);
// Create current FIR filter
filter_create_fir_lowpass((float*)current_fir_coeffs, CURR_FIR_FCUT, CURR_FIR_TAPS_BITS, 1);
TIM_DeInit(TIM1);
TIM_DeInit(TIM8);
TIM1->CNT = 0;
TIM8->CNT = 0;
// TIM1 clock enable
RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE);
// Time Base configuration
TIM_TimeBaseStructure.TIM_Prescaler = 0;
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
TIM_TimeBaseStructure.TIM_Period = SYSTEM_CORE_CLOCK / (int)switching_frequency_now;
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
TIM_TimeBaseStructure.TIM_RepetitionCounter = 0;
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 = conf_general_calculate_deadtime(HW_DEAD_TIME_NSEC, SYSTEM_CORE_CLOCK);
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!
*/
ADC_CommonInitTypeDef ADC_CommonInitStructure;
DMA_InitTypeDef DMA_InitStructure;
ADC_InitTypeDef ADC_InitStructure;
// Clock
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA2 | RCC_AHB1Periph_GPIOA | RCC_AHB1Periph_GPIOC, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1 | RCC_APB2Periph_ADC2 | RCC_APB2Periph_ADC3, ENABLE);
dmaStreamAllocate(STM32_DMA_STREAM(STM32_DMA_STREAM_ID(2, 4)),
5,
(stm32_dmaisr_t)mcpwm_adc_int_handler,
(void *)0);
// 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 = HW_ADC_CHANNELS;
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);
// Enable transfer complete interrupt
DMA_ITConfig(DMA2_Stream4, DMA_IT_TC, 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_RegSimult;
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_T8_CC1;
ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
ADC_InitStructure.ADC_NbrOfConversion = HW_ADC_NBR_CONV;
ADC_Init(ADC1, &ADC_InitStructure);
ADC_InitStructure.ADC_ExternalTrigConvEdge = ADC_ExternalTrigConvEdge_None;
ADC_InitStructure.ADC_ExternalTrigConv = 0;
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);
#ifdef HW_HAS_3_SHUNTS
ADC_ExternalTrigInjectedConvConfig(ADC3, ADC_ExternalTrigInjecConv_T8_CC3);
#endif
ADC_ExternalTrigInjectedConvEdgeConfig(ADC1, ADC_ExternalTrigInjecConvEdge_Falling);
ADC_ExternalTrigInjectedConvEdgeConfig(ADC2, ADC_ExternalTrigInjecConvEdge_Falling);
#ifdef HW_HAS_3_SHUNTS
ADC_ExternalTrigInjectedConvEdgeConfig(ADC3, ADC_ExternalTrigInjecConvEdge_Falling);
#endif
ADC_InjectedSequencerLengthConfig(ADC1, HW_ADC_INJ_CHANNELS);
ADC_InjectedSequencerLengthConfig(ADC2, HW_ADC_INJ_CHANNELS);
#ifdef HW_HAS_3_SHUNTS
ADC_InjectedSequencerLengthConfig(ADC3, HW_ADC_INJ_CHANNELS);
#endif
hw_setup_adc_channels();
// Interrupt
ADC_ITConfig(ADC1, ADC_IT_JEOC, ENABLE);
nvicEnableVector(ADC_IRQn, 6);
// Enable ADC1
ADC_Cmd(ADC1, ENABLE);
// Enable ADC2
ADC_Cmd(ADC2, ENABLE);
// Enable ADC3
ADC_Cmd(ADC3, ENABLE);
// ------------- Timer8 for ADC sampling ------------- //
// Time Base configuration
RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM8, ENABLE);
TIM_TimeBaseStructure.TIM_Prescaler = 0;
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
TIM_TimeBaseStructure.TIM_Period = 0xFFFF;
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
TIM_TimeBaseStructure.TIM_RepetitionCounter = 0;
TIM_TimeBaseInit(TIM8, &TIM_TimeBaseStructure);
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
TIM_OCInitStructure.TIM_Pulse = 500;
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(TIM8, &TIM_OCInitStructure);
TIM_OC1PreloadConfig(TIM8, TIM_OCPreload_Enable);
TIM_OC2Init(TIM8, &TIM_OCInitStructure);
TIM_OC2PreloadConfig(TIM8, TIM_OCPreload_Enable);
TIM_OC3Init(TIM8, &TIM_OCInitStructure);
TIM_OC3PreloadConfig(TIM8, TIM_OCPreload_Enable);
TIM_ARRPreloadConfig(TIM8, ENABLE);
TIM_CCPreloadControl(TIM8, ENABLE);
// PWM outputs have to be enabled in order to trigger ADC on CCx
TIM_CtrlPWMOutputs(TIM8, ENABLE);
// TIM1 Master and TIM8 slave
TIM_SelectOutputTrigger(TIM1, TIM_TRGOSource_Update);
TIM_SelectMasterSlaveMode(TIM1, TIM_MasterSlaveMode_Enable);
TIM_SelectInputTrigger(TIM8, TIM_TS_ITR0);
TIM_SelectSlaveMode(TIM8, TIM_SlaveMode_Reset);
// Enable TIM1 and TIM8
TIM_Cmd(TIM1, ENABLE);
TIM_Cmd(TIM8, ENABLE);
// Main Output Enable
TIM_CtrlPWMOutputs(TIM1, ENABLE);
// ADC sampling locations
stop_pwm_hw();
mc_timer_struct timer_tmp;
timer_tmp.top = TIM1->ARR;
timer_tmp.duty = TIM1->ARR / 2;
update_adc_sample_pos(&timer_tmp);
set_next_timer_settings(&timer_tmp);
utils_sys_unlock_cnt();
CURRENT_FILTER_ON();
// Calibrate current offset
ENABLE_GATE();
DCCAL_OFF();
do_dc_cal();
// Start threads
timer_thd_stop = false;
rpm_thd_stop = false;
chThdCreateStatic(timer_thread_wa, sizeof(timer_thread_wa), NORMALPRIO, timer_thread, NULL);
chThdCreateStatic(rpm_thread_wa, sizeof(rpm_thread_wa), NORMALPRIO, rpm_thread, NULL);
// Check if the system has resumed from IWDG reset
if (timeout_had_IWDG_reset()) {
mc_interface_fault_stop(FAULT_CODE_BOOTING_FROM_WATCHDOG_RESET, false, false);
}
// Reset tachometers again
tachometer = 0;
tachometer_abs = 0;
init_done = true;
}
void mcpwm_deinit(void) {
if (!init_done) {
return;
}
init_done = false;
timer_thd_stop = true;
rpm_thd_stop = true;
while (timer_thd_stop || rpm_thd_stop) {
chThdSleepMilliseconds(1);
}
TIM_DeInit(TIM1);
TIM_DeInit(TIM8);
ADC_DeInit();
DMA_DeInit(DMA2_Stream4);
nvicDisableVector(ADC_IRQn);
dmaStreamRelease(STM32_DMA_STREAM(STM32_DMA_STREAM_ID(2, 4)));
}
bool mcpwm_init_done(void) {
return init_done;
}
void mcpwm_set_configuration(volatile mc_configuration *configuration) {
// Stop everything first to be safe
control_mode = CONTROL_MODE_NONE;
stop_pwm_ll();
utils_sys_lock_cnt();
conf = configuration;
comm_mode_next = conf->comm_mode;
mcpwm_init_hall_table((int8_t*)conf->hall_table);
update_sensor_mode();
utils_sys_unlock_cnt();
}
/**
* Initialize the hall sensor lookup table
*
* @param table
* The commutations corresponding to the hall sensor states in the forward direction-
*/
void mcpwm_init_hall_table(int8_t *table) {
const int fwd_to_rev[7] = {-1,1,6,5,4,3,2};
for (int i = 0;i < 8;i++) {
hall_to_phase_table[8 + i] = table[i];
int ind_now = hall_to_phase_table[8 + i];
if (ind_now < 1) {
hall_to_phase_table[i] = ind_now;
continue;
}
hall_to_phase_table[i] = fwd_to_rev[ind_now];
}
}
static void do_dc_cal(void) {
DCCAL_ON();
// Wait max 5 seconds
int cnt = 0;
while(IS_DRV_FAULT()){
chThdSleepMilliseconds(1);
cnt++;
if (cnt > 5000) {
break;
}
};
chThdSleepMilliseconds(1000);
curr0_sum = 0;
curr1_sum = 0;
#ifdef HW_HAS_3_SHUNTS
curr2_sum = 0;
#endif
curr_start_samples = 0;
while(curr_start_samples < 4000) {};
curr0_offset = curr0_sum / curr_start_samples;
curr1_offset = curr1_sum / curr_start_samples;
#ifdef HW_HAS_3_SHUNTS
curr2_offset = curr2_sum / curr_start_samples;
#endif
DCCAL_OFF();
dccal_done = true;
}
static void pll_run(float phase, float dt, volatile float *phase_var,
volatile float *speed_var) {
UTILS_NAN_ZERO(*phase_var);
float delta_theta = phase - *phase_var;
utils_norm_angle_rad(&delta_theta);
UTILS_NAN_ZERO(*speed_var);
*phase_var += (*speed_var + conf->foc_pll_kp * delta_theta) * dt;
utils_norm_angle_rad((float*)phase_var);
*speed_var += conf->foc_pll_ki * delta_theta * dt;
}
/**
* Use duty cycle control. Absolute values less than MCPWM_MIN_DUTY_CYCLE will
* stop the motor.
*
* @param dutyCycle
* The duty cycle to use.
*/
void mcpwm_set_duty(float dutyCycle) {
control_mode = CONTROL_MODE_DUTY;
set_duty_cycle_hl(dutyCycle);
}
/**
* Use duty cycle control. Absolute values less than MCPWM_MIN_DUTY_CYCLE will
* stop the motor.
*
* WARNING: This function does not use ramping. A too large step with a large motor
* can destroy hardware.
*
* @param dutyCycle
* The duty cycle to use.
*/
void mcpwm_set_duty_noramp(float dutyCycle) {
control_mode = CONTROL_MODE_DUTY;
if (state != MC_STATE_RUNNING) {
set_duty_cycle_hl(dutyCycle);
} else {
dutycycle_set = dutyCycle;
dutycycle_now = dutyCycle;
set_duty_cycle_ll(dutyCycle);
}
}
/**
* Use PID rpm control. Note that this value has to be multiplied by half of
* the number of motor poles.
*
* @param rpm
* The electrical RPM goal value to use.
*/
void mcpwm_set_pid_speed(float rpm) {
control_mode = CONTROL_MODE_SPEED;
speed_pid_set_rpm = rpm;
}
/**
* Use PID position control. Note that this only works when encoder support
* is enabled.
*
* @param pos
* The desired position of the motor in degrees.
*/
void mcpwm_set_pid_pos(float pos) {
control_mode = CONTROL_MODE_POS;
pos_pid_set_pos = pos;
if (state != MC_STATE_RUNNING) {
set_duty_cycle_hl(conf->l_min_duty);
}
}
/**
* Use current control and specify a goal current to use. The sign determines
* the direction of the torque. Absolute values less than
* conf->cc_min_current will release the motor.
*
* @param current
* The current to use.
*/
void mcpwm_set_current(float current) {
if (fabsf(current) < conf->cc_min_current) {
control_mode = CONTROL_MODE_NONE;
stop_pwm_ll();
return;
}
utils_truncate_number(¤t, -conf->l_current_max * conf->l_current_max_scale,
conf->l_current_max * conf->l_current_max_scale);
control_mode = CONTROL_MODE_CURRENT;
current_set = current;
if (state != MC_STATE_RUNNING) {
set_duty_cycle_hl(SIGN(current) * conf->l_min_duty);
}
}
/**
* Brake the motor with a desired current. Absolute values less than
* conf->cc_min_current will release the motor.
*
* @param current
* The current to use. Positive and negative values give the same effect.
*/
void mcpwm_set_brake_current(float current) {
if (fabsf(current) < conf->cc_min_current) {
control_mode = CONTROL_MODE_NONE;
stop_pwm_ll();
return;
}
utils_truncate_number(¤t, -fabsf(conf->lo_current_min), fabsf(conf->lo_current_min));
control_mode = CONTROL_MODE_CURRENT_BRAKE;
current_set = current;
if (state != MC_STATE_RUNNING && state != MC_STATE_FULL_BRAKE) {
// In case the motor is already spinning, set the state to running
// so that it can be ramped down before the full brake is applied.
if (conf->motor_type == MOTOR_TYPE_DC) {
if (fabsf(dutycycle_now) > 0.1) {
state = MC_STATE_RUNNING;
} else {
full_brake_ll();
}
} else {
if (fabsf(rpm_now) > conf->l_max_erpm_fbrake) {
state = MC_STATE_RUNNING;
} else {
full_brake_ll();
}
}
}
}
/**
* Get the electrical position (or commutation step) of the motor.
*
* @return
* The current commutation step. Range [1 6]
*/
int mcpwm_get_comm_step(void) {
return comm_step;
}
float mcpwm_get_duty_cycle_set(void) {
return dutycycle_set;
}
float mcpwm_get_duty_cycle_now(void) {
return dutycycle_now;
}
/**
* Get the current switching frequency.
*
* @return
* The switching frequency in Hz.
*/
float mcpwm_get_switching_frequency_now(void) {
return switching_frequency_now;
}
/**
* Calculate the current RPM of the motor. This is a signed value and the sign
* depends on the direction the motor is rotating in. Note that this value has
* to be divided by half the number of motor poles.
*
* @return
* The RPM value.
*/
float mcpwm_get_rpm(void) {
if (conf->motor_type == MOTOR_TYPE_DC) {
return m_pll_speed / ((2.0 * M_PI) / 60.0);
} else {
return direction ? rpm_now : -rpm_now;
}
}
mc_state mcpwm_get_state(void) {
return state;
}
/**
* Calculate the KV (RPM per volt) value for the motor. This function has to
* be used while the motor is moving. Note that the return value has to be
* divided by half the number of motor poles.
*
* @return
* The KV value.
*/
float mcpwm_get_kv(void) {
return rpm_now / (GET_INPUT_VOLTAGE() * fabsf(dutycycle_now));
}
/**
* Calculate the FIR-filtered KV (RPM per volt) value for the motor. This
* function has to be used while the motor is moving. Note that the return
* value has to be divided by half the number of motor poles.
*
* @return
* The filtered KV value.
*/
float mcpwm_get_kv_filtered(void) {
float value = filter_run_fir_iteration((float*)kv_fir_samples,
(float*)kv_fir_coeffs, KV_FIR_TAPS_BITS, kv_fir_index);
return value;
}
/**
* Get the motor current. The sign of this value will
* represent whether the motor is drawing (positive) or generating
* (negative) current.
*
* @return
* The motor current.
*/
float mcpwm_get_tot_current(void) {
return last_current_sample;
}
/**
* Get the FIR-filtered motor current. The sign of this value will
* represent whether the motor is drawing (positive) or generating
* (negative) current.
*
* @return
* The filtered motor current.
*/
float mcpwm_get_tot_current_filtered(void) {
return last_current_sample_filtered;
}
/**
* Get the motor current. The sign of this value represents the direction
* in which the motor generates torque.
*
* @return
* The motor current.
*/
float mcpwm_get_tot_current_directional(void) {
const float retval = mcpwm_get_tot_current();
return dutycycle_now > 0.0 ? retval : -retval;
}
/**
* Get the filtered motor current. The sign of this value represents the
* direction in which the motor generates torque.
*
* @return
* The filtered motor current.
*/
float mcpwm_get_tot_current_directional_filtered(void) {
const float retval = mcpwm_get_tot_current_filtered();
return dutycycle_now > 0.0 ? retval : -retval;
}
/**
* Get the input current to the motor controller.
*
* @return
* The input current.
*/
float mcpwm_get_tot_current_in(void) {
return mcpwm_get_tot_current() * fabsf(dutycycle_now);
}
/**
* Get the FIR-filtered input current to the motor controller.
*
* @return
* The filtered input current.
*/
float mcpwm_get_tot_current_in_filtered(void) {
return mcpwm_get_tot_current_filtered() * fabsf(dutycycle_now);
}
/**
* Set the number of steps the motor has rotated. This number is signed and
* becomes a negative when the motor is rotating backwards.
*
* @param steps
* New number of motor steps will be set after this call.
*
* @return
* The previous tachometer value in motor steps. The number of motor revolutions will
* be this number divided by (3 * MOTOR_POLE_NUMBER).
*/
int mcpwm_set_tachometer_value(int steps)
{
int val = tachometer;
tachometer = steps;
return val;
}
/**
* Read the number of steps the motor has rotated. This number is signed and
* will return a negative number when the motor is rotating backwards.
*
* @param reset
* If true, the tachometer counter will be reset after this call.
*
* @return
* The tachometer value in motor steps. The number of motor revolutions will
* be this number divided by (3 * MOTOR_POLE_NUMBER).
*/
int mcpwm_get_tachometer_value(bool reset) {
int val = tachometer;
if (reset) {
tachometer = 0;
}
return val;
}
/**
* Read the absolute number of steps the motor has rotated.
*
* @param reset
* If true, the tachometer counter will be reset after this call.
*
* @return
* The tachometer value in motor steps. The number of motor revolutions will
* be this number divided by (3 * MOTOR_POLE_NUMBER).
*/
int mcpwm_get_tachometer_abs_value(bool reset) {
int val = tachometer_abs;
if (reset) {
tachometer_abs = 0;
}
return val;
}
/**
* Switch off all FETs.
*/
void mcpwm_stop_pwm(void) {
control_mode = CONTROL_MODE_NONE;
stop_pwm_ll();
}
static void stop_pwm_ll(void) {
state = MC_STATE_OFF;
ignore_iterations = MCPWM_CMD_STOP_TIME;
stop_pwm_hw();
}
static void stop_pwm_hw(void) {
#ifdef HW_HAS_DRV8313
DISABLE_BR();
#endif
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);
set_switching_frequency(conf->m_bldc_f_sw_max);
}
static void full_brake_ll(void) {
state = MC_STATE_FULL_BRAKE;
ignore_iterations = MCPWM_CMD_STOP_TIME;
full_brake_hw();
}
static void full_brake_hw(void) {
#ifdef HW_HAS_DRV8313
ENABLE_BR();
#endif
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_Enable);
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_Enable);
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_Enable);
TIM_GenerateEvent(TIM1, TIM_EventSource_COM);
set_switching_frequency(conf->m_bldc_f_sw_max);
}
/**
* High-level duty cycle setter. Will set the ramping goal of the duty cycle.
* If motor is not running, it will be started in different ways depending on
* whether it is moving or not.
*
* @param dutyCycle
* The duty cycle in the range [-MCPWM_MAX_DUTY_CYCLE MCPWM_MAX_DUTY_CYCLE]
* If the absolute value of the duty cycle is less than MCPWM_MIN_DUTY_CYCLE,
* the motor phases will be shorted to brake the motor.
*/
static void set_duty_cycle_hl(float dutyCycle) {
utils_truncate_number(&dutyCycle, -conf->l_max_duty, conf->l_max_duty);
if (state == MC_STATE_DETECTING) {
stop_pwm_ll();
return;
}
dutycycle_set = dutyCycle;
if (state != MC_STATE_RUNNING) {
if (fabsf(dutyCycle) >= conf->l_min_duty) {
// dutycycle_now is updated by the back-emf detection. If the motor already
// is spinning, it will be non-zero.
if (fabsf(dutycycle_now) < conf->l_min_duty) {
dutycycle_now = SIGN(dutyCycle) * conf->l_min_duty;
}
set_duty_cycle_ll(dutycycle_now);
} else {
// In case the motor is already spinning, set the state to running
// so that it can be ramped down before the full brake is applied.
if (conf->motor_type == MOTOR_TYPE_DC) {
if (fabsf(dutycycle_now) > 0.1) {
state = MC_STATE_RUNNING;
} else {
full_brake_ll();
}
} else {
if (fabsf(rpm_now) > conf->l_max_erpm_fbrake) {
state = MC_STATE_RUNNING;