SimpleFOClibrary  2.1
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 */
9 HallSensor::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 
44 void HallSensor::updateState() {
45  long new_pulse_timestamp = _micros();
46 
47  int8_t new_hall_state = C_active + (B_active << 1) + (A_active << 2);
48 
49  // glitch avoidance #1 - sometimes we get an interrupt but pins haven't changed
50  if (new_hall_state == hall_state) {
51  return;
52  }
53  hall_state = new_hall_state;
54 
55  int8_t new_electric_sector = ELECTRIC_SECTORS[hall_state];
56  static Direction old_direction;
57  if (new_electric_sector - electric_sector > 3) {
58  //underflow
61  } else if (new_electric_sector - electric_sector < (-3)) {
62  //overflow
65  } else {
66  direction = (new_electric_sector > electric_sector)? Direction::CW : Direction::CCW;
67  }
68  electric_sector = new_electric_sector;
69 
70  // glitch avoidance #2 changes in direction can cause velocity spikes. Possible improvements needed in this area
71  if (direction == old_direction) {
72  // not oscilating or just changed direction
73  pulse_diff = new_pulse_timestamp - pulse_timestamp;
74  } else {
75  pulse_diff = 0;
76  }
77 
78  pulse_timestamp = new_pulse_timestamp;
80  old_direction = direction;
81  if (onSectorChange != nullptr) onSectorChange(electric_sector);
82 }
83 
91 void HallSensor::attachSectorCallback(void (*_onSectorChange)(int sector)) {
92  onSectorChange = _onSectorChange;
93 }
94 
95 /*
96  Shaft angle calculation
97 */
99  return ((electric_rotations * 6 + electric_sector) / cpr) * _2PI ;
100 }
101 
102 /*
103  Shaft velocity calculation
104  function using mixed time and frequency measurement technique
105 */
107  if (pulse_diff == 0 || ((_micros() - pulse_timestamp) > pulse_diff) ) { // last velocity isn't accurate if too old
108  return 0;
109  } else {
110  return direction * (_2PI / cpr) / (pulse_diff / 1000000.0);
111  }
112 
113 }
114 
115 // HallSensor initialisation of the hardware pins
116 // and calculation variables
118  // initialise the electrical rotations to 0
119  electric_rotations = 0;
120 
121  // HallSensor - check if pullup needed for your HallSensor
122  if(pullup == Pullup::INTERN){
123  pinMode(pinA, INPUT_PULLUP);
124  pinMode(pinB, INPUT_PULLUP);
125  pinMode(pinC, INPUT_PULLUP);
126  }else{
127  pinMode(pinA, INPUT);
128  pinMode(pinB, INPUT);
129  pinMode(pinC, INPUT);
130  }
131 
132  // init hall_state
133  A_active= digitalRead(pinA);
134  B_active = digitalRead(pinB);
135  C_active = digitalRead(pinC);
136  updateState();
137 
138  pulse_timestamp = _micros();
139 
140 }
141 
142 // function enabling hardware interrupts for the callback provided
143 // if callback is not provided then the interrupt is not enabled
144 void HallSensor::enableInterrupts(void (*doA)(), void(*doB)(), void(*doC)()){
145  // attach interrupt if functions provided
146 
147  // A, B and C callback
148  if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE);
149  if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE);
150  if(doC != nullptr) attachInterrupt(digitalPinToInterrupt(pinC), doC, CHANGE);
151 }
152 
HallSensor::cpr
float cpr
HallSensor cpr number.
Definition: HallSensor.h:53
HallSensor::direction
Direction direction
Definition: HallSensor.h:62
CW
@ CW
Definition: Sensor.h:8
HallSensor::pinA
int pinA
HallSensor hardware pin A.
Definition: HallSensor.h:47
HallSensor::pinC
int pinC
HallSensor hardware pin C.
Definition: HallSensor.h:49
HallSensor::enableInterrupts
void enableInterrupts(void(*doA)()=nullptr, void(*doB)()=nullptr, void(*doC)()=nullptr)
Definition: HallSensor.cpp:144
INTERN
@ INTERN
Use internal pullups.
Definition: Sensor.h:18
EXTERN
@ EXTERN
Use external pullups.
Definition: Sensor.h:19
HallSensor::pinB
int pinB
HallSensor hardware pin B.
Definition: HallSensor.h:48
HallSensor::getAngle
float getAngle() override
Definition: HallSensor.cpp:98
HallSensor::handleC
void handleC()
Definition: HallSensor.cpp:36
_2PI
#define _2PI
Definition: foc_utils.h:23
CCW
@ CCW
Definition: Sensor.h:9
HallSensor::getVelocity
float getVelocity() override
Definition: HallSensor.cpp:106
HallSensor.h
HallSensor::handleB
void handleB()
Definition: HallSensor.cpp:30
Direction
Direction
Definition: Sensor.h:7
HallSensor::hall_state
volatile int8_t hall_state
Definition: HallSensor.h:67
_micros
unsigned long _micros()
Definition: time_utils.cpp:21
HallSensor::electric_rotations
volatile long electric_rotations
Definition: HallSensor.h:71
HallSensor::electric_sector
volatile int8_t electric_sector
Definition: HallSensor.h:69
HallSensor::init
void init()
Definition: HallSensor.cpp:117
HallSensor::total_interrupts
volatile long total_interrupts
Definition: HallSensor.h:73
HallSensor::handleA
void handleA()
Definition: HallSensor.cpp:25
ELECTRIC_SECTORS
const int8_t ELECTRIC_SECTORS[8]
Definition: HallSensor.h:10
HallSensor::attachSectorCallback
void attachSectorCallback(void(*onSectorChange)(int a)=nullptr)
Definition: HallSensor.cpp:91
HallSensor::HallSensor
HallSensor(int encA, int encB, int encC, int pp)
Definition: HallSensor.cpp:9
HallSensor::pullup
Pullup pullup
Configuration parameter internal or external pullups.
Definition: HallSensor.h:52