SimpleFOClibrary 2.4.0
Loading...
Searching...
No Matches
HallSensor.cpp
Go to the documentation of this file.
1#include "HallSensor.h"
2
3
4/*
5 HallSensor(int hallA, int hallB , int cpr, int index)
6 - hallA, hallB, hallC - HallSensor A, B and C pins
7 - pp - pole pairs
8*/
9HallSensor::HallSensor(int _hallA, int _hallB, int _hallC, int _pp){
10
11 // hardware pins
12 pinA = _hallA;
13 pinB = _hallB;
14 pinC = _hallC;
15
16 // hall has 6 segments per electrical revolution
17 cpr = _pp * 6;
18
19 // extern pullup as default
21}
22
23// HallSensor interrupt callback functions
24// A channel
26 A_active= digitalRead(pinA);
27 updateState();
28}
29// B channel
31 B_active = digitalRead(pinB);
32 updateState();
33}
34
35// C channel
37 C_active = digitalRead(pinC);
38 updateState();
39}
40
41/**
42 * Updates the state and sector following an interrupt
43 */
44void HallSensor::updateState() {
45 int8_t new_hall_state = C_active + (B_active << 1) + (A_active << 2);
46
47 // glitch avoidance #1 - sometimes we get an interrupt but pins haven't changed
48 if (new_hall_state == hall_state) return;
49
50 long new_pulse_timestamp = _micros();
51 hall_state = new_hall_state;
52
53 int8_t new_electric_sector = ELECTRIC_SECTORS[hall_state];
54 int8_t electric_sector_dif = new_electric_sector - electric_sector;
55 if (electric_sector_dif > 3) {
56 //underflow
59 } else if (electric_sector_dif < (-3)) {
60 //overflow
63 } else {
64 direction = (new_electric_sector > electric_sector)? Direction::CW : Direction::CCW;
65 }
66 electric_sector = new_electric_sector;
67
68 // glitch avoidance #2 changes in direction can cause velocity spikes. Possible improvements needed in this area
69 if (direction == old_direction) {
70 // not oscilating or just changed direction
71 pulse_diff = new_pulse_timestamp - pulse_timestamp;
72 } else {
73 pulse_diff = 0;
74 }
75
76 pulse_timestamp = new_pulse_timestamp;
79 if (onSectorChange != nullptr) onSectorChange(electric_sector);
80}
81
82/**
83 * Optionally set a function callback to be fired when sector changes
84 * void onSectorChange(int sector) {
85 * ... // for debug or call driver directly?
86 * }
87 * sensor.attachSectorCallback(onSectorChange);
88 */
89void HallSensor::attachSectorCallback(void (*_onSectorChange)(int sector)) {
90 onSectorChange = _onSectorChange;
91}
92
93
94
95// Sensor update function. Safely copy volatile interrupt variables into Sensor base class state variables.
97 // Copy volatile variables in minimal-duration blocking section to ensure no interrupts are missed
98 if (use_interrupt){
99 noInterrupts();
100 }else{
101 A_active = digitalRead(pinA);
102 B_active = digitalRead(pinB);
103 C_active = digitalRead(pinC);
104 updateState();
105 }
106
107 angle_prev_ts = pulse_timestamp;
108 long last_electric_rotations = electric_rotations;
109 int8_t last_electric_sector = electric_sector;
110 if (use_interrupt) interrupts();
111 angle_prev = ((float)((last_electric_rotations * 6 + last_electric_sector) % cpr) / (float)cpr) * _2PI ;
112 full_rotations = (int32_t)((last_electric_rotations * 6 + last_electric_sector) / cpr);
113}
114
115
116
117/*
118 Shaft angle calculation
119 TODO: numerical precision issue here if the electrical rotation overflows the angle will be lost
120*/
122 return ((float)(electric_rotations * 6 + electric_sector) / (float)cpr) * _2PI ;
123}
124
125/*
126 Shaft velocity calculation
127 function using mixed time and frequency measurement technique
128*/
130 noInterrupts();
131 long last_pulse_timestamp = pulse_timestamp;
132 long last_pulse_diff = pulse_diff;
133 interrupts();
134 if (last_pulse_diff == 0 || ((long)(_micros() - last_pulse_timestamp) > last_pulse_diff*2) ) { // last velocity isn't accurate if too old
135 return 0;
136 } else {
137 return direction * (_2PI / (float)cpr) / (last_pulse_diff / 1000000.0f);
138 }
139
140}
141
142// HallSensor initialisation of the hardware pins
143// and calculation variables
145 // initialise the electrical rotations to 0
147
148 // HallSensor - check if pullup needed for your HallSensor
150 pinMode(pinA, INPUT_PULLUP);
151 pinMode(pinB, INPUT_PULLUP);
152 pinMode(pinC, INPUT_PULLUP);
153 }else{
154 pinMode(pinA, INPUT);
155 pinMode(pinB, INPUT);
156 pinMode(pinC, INPUT);
157 }
158
159 // init hall_state
160 A_active = digitalRead(pinA);
161 B_active = digitalRead(pinB);
162 C_active = digitalRead(pinC);
163 updateState();
164
165 pulse_timestamp = _micros();
166
167 // we don't call Sensor::init() here because init is handled in HallSensor class.
168}
169
170// function enabling hardware interrupts for the callback provided
171// if callback is not provided then the interrupt is not enabled
172void HallSensor::enableInterrupts(void (*doA)(), void(*doB)(), void(*doC)()){
173 // attach interrupt if functions provided
174
175 // A, B and C callback
176 if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE);
177 if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE);
178 if(doC != nullptr) attachInterrupt(digitalPinToInterrupt(pinC), doC, CHANGE);
179
180 use_interrupt = true;
181}
const int8_t ELECTRIC_SECTORS[8]
Definition HallSensor.h:10
@ USE_EXTERN
Use external pullups.
Definition Sensor.h:21
@ USE_INTERN
Use internal pullups.
Definition Sensor.h:20
Direction
Definition Sensor.h:9
@ CCW
Definition Sensor.h:11
@ CW
Definition Sensor.h:10
volatile int8_t electric_sector
Definition HallSensor.h:73
void handleA()
HallSensor(int encA, int encB, int encC, int pp)
Definition HallSensor.cpp:9
int cpr
HallSensor cpr number.
Definition HallSensor.h:54
int pinB
HallSensor hardware pin B.
Definition HallSensor.h:48
int use_interrupt
True if interrupts have been attached.
Definition HallSensor.h:50
void attachSectorCallback(void(*onSectorChange)(int a)=nullptr)
float getVelocity() override
float getSensorAngle() override
Direction direction
Definition HallSensor.h:65
void handleC()
volatile long total_interrupts
Definition HallSensor.h:77
void enableInterrupts(void(*doA)()=nullptr, void(*doB)()=nullptr, void(*doC)()=nullptr)
volatile long electric_rotations
Definition HallSensor.h:75
int pinC
HallSensor hardware pin C.
Definition HallSensor.h:49
void update() override
void handleB()
Pullup pullup
Configuration parameter internal or external pullups.
Definition HallSensor.h:53
int pinA
HallSensor hardware pin A.
Definition HallSensor.h:47
Direction old_direction
Definition HallSensor.h:66
volatile int8_t hall_state
Definition HallSensor.h:71
long angle_prev_ts
Definition Sensor.h:132
int32_t full_rotations
Definition Sensor.h:135
float angle_prev
Definition Sensor.h:131
#define _2PI
Definition foc_utils.h:29
unsigned long _micros()