forked from jsphuebner/stm32-sine
-
Notifications
You must be signed in to change notification settings - Fork 1
/
inc_encoder.cpp
662 lines (585 loc) · 19.2 KB
/
inc_encoder.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
/*
* This file is part of the stm32-sine project.
*
* Copyright (C) 2011 Johannes Huebner <dev@johanneshuebner.com>
* Copyright (C) 2019 Nail Guzel
*
* This program 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.
*
* This program 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 "hwdefs.h"
#include "inc_encoder.h"
#include "my_math.h"
#include <libopencm3/stm32/timer.h>
#include <libopencm3/stm32/dma.h>
#include <libopencm3/stm32/exti.h>
#include <libopencm3/stm32/gpio.h>
#include <libopencm3/stm32/adc.h>
#include <libopencm3/stm32/rcc.h>
#include "errormessage.h"
#include "params.h"
#include "sine_core.h"
#include "printf.h"
#define TWO_PI 65536
//Angle difference at which we assume jitter to become irrelevant
#define STABLE_ANGLE ((10 * TWO_PI) / 360)
#define MAX_CNT TWO_PI - 1
#define MAX_REVCNT_VALUES 5
#define MIN_RES_AMP 1000
#define FRQ_TO_PSC(frq) ((72000000 / frq) - 1)
#define NUM_ENCODER_CONFIGS (sizeof(encoderConfigurations) / sizeof(encoderConfigurations[0]))
typedef struct EncoderConfiguration
{
uint32_t pulseMeasFrequency;
enum tim_ic_filter resetFilter;
enum tim_ic_filter captureFilter;
uint16_t maxPpr;
} ENCODER_CONFIG;
static const ENCODER_CONFIG encoderConfigurations[] =
{
{ 1000000, TIM_IC_DTF_DIV_32_N_8, TIM_IC_DTF_DIV_32_N_6, 60 }, // CFG1 - this will be selected for numimp <= 60
{ 2400000, TIM_IC_DTF_DIV_2_N_8, TIM_IC_DTF_DIV_2_N_6, 125 }, // CFG2 - this will be selected for numimp <= 125
{ 7200000, TIM_IC_DTF_DIV_2_N_8, TIM_IC_DTF_DIV_2_N_6, 8192 }, // CFG3 - this will be selected for numimp <= 8192
};
static const ENCODER_CONFIG * selectedConfig = &encoderConfigurations[0];
static uint32_t pulseMeasFrq = selectedConfig->pulseMeasFrequency;
//Delay in us between generating an edge on the exciter output and measuring the
//Return values via ADC - Found this by scoping
static const uint16_t resolverSampleDelay = 40;
static volatile uint16_t timdata[MAX_REVCNT_VALUES];
static volatile uint16_t angle = 0;
static uint16_t pulsesPerTurn = 0;
static uint32_t lastPulseTimespan = 0;
static uint32_t anglePerPulse = 0;
static uint32_t fullTurns = 0;
static uint32_t pwmFrq = 1;
static s32fp lastFrequency = 0;
static bool ignore = true;
static enum Encoder::mode encMode = Encoder::INVALID;
static bool seenNorthSignal = false;
static int32_t turnsSinceLastSample = 0;
static int32_t distance = 0;
static int32_t resolverMin = 0, resolverMax = 0, startupDelay;
static int32_t sinChan = 3, cosChan = 2;
static int32_t detectedDirection = 0;
static uint16_t sincosoffs = 2048;
void Encoder::Reset()
{
ignore = true;
lastPulseTimespan = MAX_CNT;
resolverMin = 0;
resolverMax = 0;
lastFrequency = 0;
detectedDirection = 0;
startupDelay = 4000;
for (uint32_t i = 0; i < MAX_REVCNT_VALUES; i++)
timdata[i] = MAX_CNT;
}
/** Since power up, have we seen the north marker? */
bool Encoder::SeenNorthSignal()
{
return seenNorthSignal;
}
/** Set type of motor position feedback
* @param mode type of motor position feedback */
void Encoder::SetMode(Encoder::mode mode)
{
if (encMode == mode) return;
encMode = mode;
switch (mode)
{
case AB:
case ABZ:
InitTimerABZMode();
break;
case SINGLE:
InitTimerSingleChannelMode();
break;
case SPI:
InitSPIMode();
break;
case RESOLVER:
case SINCOS:
InitResolverMode();
break;
default:
break;
}
}
void Encoder::SetPwmFrequency(uint32_t frq)
{
pwmFrq = frq;
}
void Encoder::SetSinCosOffset(uint16_t offset)
{
sincosoffs = offset;
}
/** set number of impulses per shaft rotation
*/
void Encoder::SetImpulsesPerTurn(uint16_t imp)
{
if (imp == pulsesPerTurn) return;
pulsesPerTurn = imp;
anglePerPulse = TWO_PI / imp;
if (encMode == SINGLE)
InitTimerSingleChannelMode();
if (encMode == AB || encMode == ABZ)
InitTimerABZMode();
}
void Encoder::SwapSinCos(bool swap)
{
if (swap)
{
sinChan = 2;
cosChan = 3;
}
else
{
sinChan = 3;
cosChan = 2;
}
}
void Encoder::UpdateRotorAngle(int dir)
{
static uint16_t lastAngle = 0;
static uint16_t accumulatedAngle = 0;
static int poleCounter = 0;
uint32_t cntVal;
int16_t numPulses;
uint32_t timeSinceLastPulse;
uint16_t interpolatedAngle;
int16_t angleDiff;
switch (encMode)
{
case AB:
case ABZ:
cntVal = timer_get_counter(REV_CNT_TIMER);
cntVal *= TWO_PI;
cntVal /= pulsesPerTurn * 4;
angle = (uint16_t)cntVal;
detectedDirection = (TIM_CR1(REV_CNT_TIMER) & TIM_CR1_DIR_DOWN) ? -1 : 1;
angleDiff = angle - lastAngle;
turnsSinceLastSample += angleDiff;
break;
case SINGLE:
numPulses = GetPulseTimeFiltered();
timeSinceLastPulse = timer_get_counter(REV_CNT_TIMER);
interpolatedAngle = ignore ? 0 : (anglePerPulse * timeSinceLastPulse) / lastPulseTimespan;
accumulatedAngle += (int16_t)(dir * numPulses * anglePerPulse);
angle = accumulatedAngle + dir * interpolatedAngle;
lastFrequency = ignore ? lastFrequency : FP_FROMINT(pulseMeasFrq) / (lastPulseTimespan * pulsesPerTurn);
detectedDirection = dir;
break;
case SPI:
angle = GetAngleSPI();
UpdateTurns(angle, lastAngle);
break;
case RESOLVER:
angle = GetAngleResolver();
UpdateTurns(angle, lastAngle);
break;
case SINCOS:
angle = GetAngleSinCos();
UpdateTurns(angle, lastAngle);
break;
default:
break;
}
if (lastAngle <= (TWO_PI / 2) && angle > (TWO_PI / 2))
{
if (poleCounter == 0)
{
fullTurns++;
poleCounter = Param::GetInt(Param::respolepairs);
}
else
{
poleCounter--;
}
}
startupDelay = startupDelay > 0 ? startupDelay - 1 : 0;
lastAngle = angle;
}
/** Update rotor frequency.
* @param callingFrequency Frequency at which this function is called in Hz
*/
void Encoder::UpdateRotorFrequency(int callingFrequency)
{
distance += turnsSinceLastSample;
if ((encMode == AB) || (encMode == ABZ))
{
//65536 is one turn
lastFrequency = (callingFrequency * turnsSinceLastSample) / FP_TOINT(TWO_PI);
turnsSinceLastSample = 0;
}
else if ((encMode == RESOLVER) || (encMode == SPI) || (encMode == SINCOS))
{
int absTurns = ABS(turnsSinceLastSample);
if (startupDelay == 0 && absTurns > STABLE_ANGLE)
{
lastFrequency = (callingFrequency * absTurns) / FP_TOINT(TWO_PI);
detectedDirection = turnsSinceLastSample > 0 ? 1 : -1;
}
else
{
lastFrequency = 0;
}
turnsSinceLastSample = 0;
}
}
/** Returns current angle of motor shaft to some arbitrary 0-axis
* @return angle in digit (2Pi=65536)
*/
uint16_t Encoder::GetRotorAngle()
{
return angle;
}
/** Return rotor frequency in Hz
* @pre in AB/ABZ encoder mode UpdateRotorFrequency must be called at a regular interval */
s32fp Encoder::GetRotorFrequency()
{
return lastFrequency;
}
void Encoder::ResetDistance()
{
distance = 0;
}
int32_t Encoder::GetDistance()
{
return distance;
}
int Encoder::GetRotorDirection()
{
return detectedDirection;
}
/** Get current speed in rpm */
uint32_t Encoder::GetSpeed()
{
if (encMode == RESOLVER || encMode == SINCOS)
{
return FP_TOINT(60 * ABS(lastFrequency)) / Param::GetInt(Param::respolepairs);
}
else
{
return FP_TOINT(60 * ABS(lastFrequency));
}
}
/** Get number of rotor turns since power up */
uint32_t Encoder::GetFullTurns()
{
return fullTurns;
}
void Encoder::UpdateTurns(uint16_t angle, uint16_t lastAngle)
{
int signedDiff = (int)angle - (int)lastAngle;
int absDiff = ABS(signedDiff);
int sign = signedDiff < 0 ? -1 : 1;
if (absDiff > (TWO_PI / 2)) //wrap detection
{
sign = -sign;
signedDiff += sign * TWO_PI;
absDiff = ABS(signedDiff);
}
turnsSinceLastSample += signedDiff;
}
void Encoder::InitTimerSingleChannelMode()
{
const ENCODER_CONFIG* currentConfig = &encoderConfigurations[0];
for (uint8_t i = 0; i < NUM_ENCODER_CONFIGS; i++, currentConfig++)
{
if (pulsesPerTurn <= currentConfig->maxPpr)
{
if (selectedConfig != currentConfig)
{
debugf("Reconfiguring encoder timer for CFG%d", (i+1));
}
selectedConfig = currentConfig;
pulseMeasFrq = selectedConfig->pulseMeasFrequency;
break;
}
}
rcc_periph_reset_pulse(REV_CNT_TIMRST);
//Some explanation: HCLK=72MHz
//APB1-Prescaler is 2 -> 36MHz
//Timer clock source is ABP1*2 because APB1 prescaler > 1
//So clock source is 72MHz (again)
//We want the timer to run at 1MHz = 72MHz/72
//Prescaler is div-1 => 71
timer_set_prescaler(REV_CNT_TIMER, FRQ_TO_PSC(pulseMeasFrq));
timer_set_period(REV_CNT_TIMER, MAX_CNT);
timer_direction_up(REV_CNT_TIMER);
/* Reset counter on input pulse. Filter constant must be larger than that of the capture input
So that the counter value is first saved, then reset */
timer_slave_set_mode(REV_CNT_TIMER, TIM_SMCR_SMS_RM); // reset mode
timer_slave_set_polarity(REV_CNT_TIMER, TIM_ET_FALLING);
if (hwRev == HW_REV1)
{
//Since channel 3 is not connected to slave mmode controller, we have to use the ETR pin
timer_slave_set_trigger(REV_CNT_TIMER, TIM_SMCR_TS_ETRF);
timer_slave_set_filter(REV_CNT_TIMER, selectedConfig->resetFilter);
gpio_set_mode(GPIOB, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, GPIO0);
}
else
{
//ETR pin not needed, can use channel 1 (after filter)
timer_slave_set_trigger(REV_CNT_TIMER, TIM_SMCR_TS_TI1FP1);
gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, GPIO6 | GPIO7);
}
/* Save timer value on input pulse with smaller filter constant */
timer_ic_set_filter(REV_CNT_TIMER, REV_CNT_IC, selectedConfig->captureFilter);
timer_ic_set_input(REV_CNT_TIMER, REV_CNT_IC, TIM_IC_IN_TI1);
timer_set_oc_polarity_low(REV_CNT_TIMER, REV_CNT_OC);
timer_ic_enable(REV_CNT_TIMER, REV_CNT_IC);
timer_enable_irq(REV_CNT_TIMER, REV_CNT_DMAEN);
timer_set_dma_on_compare_event(REV_CNT_TIMER);
timer_generate_event(REV_CNT_TIMER, TIM_EGR_UG);
timer_enable_counter(REV_CNT_TIMER);
gpio_set_mode(NORTH_EXC_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, NORTH_EXC_PIN);
exti_disable_request(NORTH_EXC_EXTI);
dma_disable_channel(DMA1, REV_CNT_DMACHAN);
dma_set_peripheral_address(DMA1, REV_CNT_DMACHAN, REV_CNT_CCR_PTR);
dma_set_memory_address(DMA1, REV_CNT_DMACHAN, (uint32_t)timdata);
dma_set_peripheral_size(DMA1, REV_CNT_DMACHAN, DMA_CCR_PSIZE_16BIT);
dma_set_memory_size(DMA1, REV_CNT_DMACHAN, DMA_CCR_MSIZE_16BIT);
dma_set_number_of_data(DMA1, REV_CNT_DMACHAN, MAX_REVCNT_VALUES);
dma_enable_memory_increment_mode(DMA1, REV_CNT_DMACHAN);
dma_enable_circular_mode(DMA1, REV_CNT_DMACHAN);
dma_enable_channel(DMA1, REV_CNT_DMACHAN);
}
void Encoder::InitSPIMode()
{
rcc_periph_reset_pulse(REV_CNT_TIMRST);
exti_disable_request(NORTH_EXC_EXTI);
gpio_set_mode(NORTH_EXC_PORT, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, NORTH_EXC_PIN);
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, GPIO7);
gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, GPIO6);
seenNorthSignal = true;
}
void Encoder::InitTimerABZMode()
{
rcc_periph_reset_pulse(REV_CNT_TIMRST);
timer_set_period(REV_CNT_TIMER, 4 * pulsesPerTurn - 1); //2 channels and 2 edges -> 4 times the number of base pulses
//In sync mode start out in reset mode and switch to encoder
//mode once the north marker has been detected
if (encMode == Encoder::ABZ)
{
exti_select_source(NORTH_EXC_EXTI, NORTH_EXC_PORT);
exti_set_trigger(NORTH_EXC_EXTI, EXTI_TRIGGER_RISING);
exti_enable_request(NORTH_EXC_EXTI);
}
else
{
exti_disable_request(NORTH_EXC_EXTI);
}
timer_slave_set_mode(REV_CNT_TIMER, TIM_SMCR_SMS_EM3); // encoder mode
timer_ic_set_input(REV_CNT_TIMER, TIM_IC1, TIM_IC_IN_TI1);
timer_ic_set_input(REV_CNT_TIMER, TIM_IC2, TIM_IC_IN_TI2);
timer_ic_set_filter(REV_CNT_TIMER, TIM_IC1, TIM_IC_DTF_DIV_32_N_8);
timer_ic_set_filter(REV_CNT_TIMER, TIM_IC2, TIM_IC_DTF_DIV_32_N_8);
timer_ic_enable(REV_CNT_TIMER, TIM_IC1);
timer_ic_enable(REV_CNT_TIMER, TIM_IC2);
timer_enable_counter(REV_CNT_TIMER);
gpio_set_mode(NORTH_EXC_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, NORTH_EXC_PIN);
gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, GPIO6 | GPIO7);
seenNorthSignal = false;
}
void Encoder::InitResolverMode()
{
//The first injected channel is always noisy, so we insert one dummy channel
uint8_t channels[3] = { 6, 6, 7 };
adc_set_injected_sequence(ADC1, sizeof(channels), channels);
adc_enable_external_trigger_injected(ADC1, ADC_CR2_JEXTSEL_JSWSTART);
adc_set_sample_time(ADC1, 6, ADC_SMPR_SMP_1DOT5CYC);
adc_set_sample_time(ADC1, 7, ADC_SMPR_SMP_1DOT5CYC);
gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, GPIO6 | GPIO7);
exti_disable_request(NORTH_EXC_EXTI);
if (encMode == RESOLVER)
{
rcc_periph_reset_pulse(REV_CNT_TIMRST);
timer_set_prescaler(REV_CNT_TIMER, 71); //run at 1MHz
timer_set_period(REV_CNT_TIMER, 65535);
timer_one_shot_mode(REV_CNT_TIMER);
timer_set_oc_mode(REV_CNT_TIMER, TIM_OC4, TIM_OCM_PWM2);
timer_enable_oc_output(REV_CNT_TIMER, TIM_OC4); //OC4 is connected to ADC trigger
timer_enable_preload(REV_CNT_TIMER);
timer_direction_up(REV_CNT_TIMER);
timer_generate_event(REV_CNT_TIMER, TIM_EGR_UG);
gpio_set_mode(NORTH_EXC_PORT, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, NORTH_EXC_PIN);
adc_set_injected_offset(ADC1, 2, 0);
adc_set_injected_offset(ADC1, 3, 0);
adc_start_conversion_injected(ADC1); //Determine offset
while (!adc_eoc_injected(ADC1));
int ch1 = adc_read_injected(ADC1, 2);
int ch2 = adc_read_injected(ADC1, 3);
adc_set_injected_offset(ADC1, 2, ch1);
adc_set_injected_offset(ADC1, 3, ch2);
adc_enable_external_trigger_injected(ADC1, ADC_CR2_JEXTSEL_TIM3_CC4);
if (CHK_BIPOLAR_OFS(ch1) || CHK_BIPOLAR_OFS(ch2))
{
ErrorMessage::Post(ERR_HIRESOFS);
}
}
else //SINCOS
{
//Offset assumed 3.3V/2 - 2048
//on my hardware, min is 0.465V, max is 2.510v, so offset is 1.4875v, or 1846
//this should be a parameter?
adc_set_injected_offset(ADC1, 2, sincosoffs);
adc_set_injected_offset(ADC1, 3, sincosoffs);
}
seenNorthSignal = true;
}
/** Gets angle from an AD2S chip */
uint16_t Encoder::GetAngleSPI()
{
uint32_t d = 0;
//Skip the abstraction, we need speed here
GPIO_BSRR(GPIOA) = GPIO7; //Clock high
GPIO_BRR(NORTH_EXC_PORT) = NORTH_EXC_PIN;
for (int i = 15; i >= 0; i--)
{
GPIO_BRR(GPIOA) = GPIO7;
uint32_t bit = ((uint32_t)GPIO_IDR(GPIOA) & GPIO6);
GPIO_BSRR(GPIOA) = GPIO7;
d |= bit << i;
}
GPIO_BSRR(NORTH_EXC_PORT) = NORTH_EXC_PIN; //Read high
d >>= 10; //6 because of GPIO6, 4 because of encoder format
//Encoder format is ANGLE[11:0], RDVEL, Parity, DOS, LOT
return d << 4; //we want 16-bit representation
}
/** Calculates current angle from resolver feedback
* and generates square wave that is filtered
* into a sine wave for resolver excitation
*/
uint16_t Encoder::GetAngleResolver()
{
if (gpio_get(NORTH_EXC_PORT, NORTH_EXC_PIN))
{
gpio_clear(NORTH_EXC_PORT, NORTH_EXC_PIN);
/* The phase delay of the 3-pole filter, amplifier and resolver is 305 degrees
That is 125 degrees after the falling edge of the exciting square wave */
timer_set_oc_value(REV_CNT_TIMER, TIM_OC4, resolverSampleDelay);
timer_set_counter(REV_CNT_TIMER, 0);
timer_enable_counter(REV_CNT_TIMER);
angle = DecodeAngle(true);
}
else
{
gpio_set(NORTH_EXC_PORT, NORTH_EXC_PIN);
timer_set_counter(REV_CNT_TIMER, 0);
timer_enable_counter(REV_CNT_TIMER);
angle = DecodeAngle(false);
}
return angle;
}
/** Calculates angle from a Hall sin/cos encoder like MLX90380 */
uint16_t Encoder::GetAngleSinCos()
{
uint16_t calcAngle = DecodeAngle(false);
adc_start_conversion_injected(ADC1);
return calcAngle;
}
/** Calculates angle from sin and cos value
* @param invert flip values to positive side in order to read a resolver modulated signal on negative edge
*/
uint16_t Encoder::DecodeAngle(bool invert)
{
int sin = adc_read_injected(ADC1, sinChan);
int cos = adc_read_injected(ADC1, cosChan);
//Wait for signal to reach usable amplitude
if ((resolverMax - resolverMin) > MIN_RES_AMP)
{
if (invert)
return SineCore::Atan2(-sin, -cos);
return SineCore::Atan2(sin, cos);
}
else
{
int temp = MIN(sin, cos);
resolverMin = MIN(temp, resolverMin);
temp = MAX(sin, cos);
resolverMax = MAX(temp, resolverMax);
if (0 == startupDelay)
{
ErrorMessage::Post(ERR_LORESAMP);
}
return 0;
}
}
int Encoder::GetPulseTimeFiltered()
{
static int lastN = 0;
static int noMovement = 0;
int n = dma_get_number_of_data(DMA1, REV_CNT_DMACHAN);
int measTm = timer_get_ic_value(REV_CNT_TIMER, REV_CNT_IC);
int pulses = n <= lastN ? lastN - n : lastN + MAX_REVCNT_VALUES - n;
int max = 0;
int min = 0xFFFF;
lastN = n;
GetMinMaxTime(min, max);
if (pulses > 0)
{
noMovement = 0;
ignore = false;
}
else
{
noMovement++;
}
//If we haven't seen movement for 1000 cycles, we assume the motor is stopped
//The time that 1000 cycles corresponds to is dependent from the calling
//frequency, i.e. the PWM frequency. The results proved ok for 8.8kHz
if (noMovement > 1000)
{
ignore = true;
lastFrequency = 0;
for (uint32_t i = 0; i < MAX_REVCNT_VALUES; i++)
timdata[i] = MAX_CNT;
}
//spike detection, a factor of 8 between adjacent pulses is most likely caused by interference
if (max > (8 * min) && min > 0)
{
ErrorMessage::Post(ERR_ENCODER);
}
//a factor of 2 is still not stable, use the maximum
else if (max > (2 * min))
{
//lastPulseTimespan = max;
}
else
{
lastPulseTimespan = IIRFILTER(lastPulseTimespan, measTm + 1, 1);
}
return pulses;
}
void Encoder::GetMinMaxTime(int& min, int& max)
{
for (int i = 0; i < MAX_REVCNT_VALUES; i++)
{
min = MIN(min, timdata[i]);
max = MAX(max, timdata[i]);
}
}
extern "C" void exti2_isr(void)
{
exti_reset_request(EXTI2);
timer_set_counter(REV_CNT_TIMER, 0);
seenNorthSignal = true;
}
extern "C" void exti15_10_isr(void)
{
exti_reset_request(EXTI14);
timer_set_counter(REV_CNT_TIMER, 0);
seenNorthSignal = true;
}