Skip to content

Commit 39ffb63

Browse files
committed
adding an additional interrupt for hallC
1 parent 515bb79 commit 39ffb63

File tree

2 files changed

+39
-36
lines changed

2 files changed

+39
-36
lines changed

src/HallSensor.cpp

Lines changed: 31 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -2,29 +2,26 @@
22

33

44
/*
5-
HallSensor(int encA, int encB , int cpr, int index)
6-
- encA, encB - HallSensor A and B pins
7-
- cpr - counts per rotation number (cpm=ppm*4)
8-
- index pin - (optional input)
5+
HallSensor(int hallA, int hallB , int cpr, int index)
6+
- hallA, hallB, hallC - HallSensor A, B and C pins
7+
- pp - pole pairs
98
*/
109

11-
HallSensor::HallSensor(int _encA, int _encB , float _ppr, int _index){
10+
HallSensor::HallSensor(int _hallA, int _hallB, int _hallC, int _pp){
1211

1312
// HallSensor measurement structure init
1413
// hardware pins
15-
pinA = _encA;
16-
pinB = _encB;
14+
pinA = _hallA;
15+
pinB = _hallB;
16+
pinC = _hallC;
1717
// counter setup
1818
pulse_counter = 0;
1919
pulse_timestamp = 0;
2020

21-
cpr = _ppr;
21+
cpr = _pp * 6; // hall has 6 segments per electrical revolution
2222
A_active = 0;
2323
B_active = 0;
24-
I_active = 0;
25-
// index pin
26-
index_pin = _index; // its 0 if not used
27-
index_pulse_counter = 0;
24+
C_active = 0;
2825

2926
// velocity calculation variables
3027
prev_Th = 0;
@@ -34,7 +31,6 @@ HallSensor::HallSensor(int _encA, int _encB , float _ppr, int _index){
3431

3532
// extern pullup as default
3633
pullup = Pullup::EXTERN;
37-
// enable quadrature HallSensor by default
3834

3935
}
4036

@@ -61,6 +57,18 @@ void HallSensor::handleB() {
6157

6258
}
6359

60+
// C channel
61+
void HallSensor::handleC() {
62+
int C = digitalRead(pinB);
63+
64+
if ( C != C_active ) {
65+
pulse_counter += (A_active != C_active) ? 1 : -1;
66+
pulse_timestamp = _micros();
67+
C_active = C;
68+
}
69+
70+
}
71+
6472
/*
6573
Shaft angle calculation
6674
*/
@@ -109,31 +117,25 @@ float HallSensor::getVelocity(){
109117
// getter for index pin
110118
// return -1 if no index
111119
int HallSensor::needsAbsoluteZeroSearch(){
112-
return index_pulse_counter == 0;
120+
return 0;
113121
}
114122
// getter for index pin
115123
int HallSensor::hasAbsoluteZero(){
116-
return hasIndex();
124+
return 0;
117125
}
118126
// initialize counter to zero
119127
float HallSensor::initRelativeZero(){
120-
long angle_offset = -pulse_counter;
121-
pulse_counter = 0;
122-
pulse_timestamp = _micros();
123-
return _2PI * (angle_offset) / ((float)cpr);
128+
return 0.0;
124129
}
125130
// initialize index to zero
126131
float HallSensor::initAbsoluteZero(){
127-
pulse_counter -= index_pulse_counter;
128-
prev_pulse_counter = pulse_counter;
129-
return (index_pulse_counter) / ((float)cpr) * (_2PI);
132+
return 0.0;
130133
}
131134
// private function used to determine if HallSensor has index
132135
int HallSensor::hasIndex(){
133-
return index_pin != 0;
136+
return 0;
134137
}
135138

136-
137139
// HallSensor initialisation of the hardware pins
138140
// and calculation variables
139141
void HallSensor::init(){
@@ -142,11 +144,11 @@ void HallSensor::init(){
142144
if(pullup == Pullup::INTERN){
143145
pinMode(pinA, INPUT_PULLUP);
144146
pinMode(pinB, INPUT_PULLUP);
145-
if(hasIndex()) pinMode(index_pin,INPUT_PULLUP);
147+
pinMode(pinC, INPUT_PULLUP);
146148
}else{
147149
pinMode(pinA, INPUT);
148150
pinMode(pinB, INPUT);
149-
if(hasIndex()) pinMode(index_pin,INPUT);
151+
pinMode(pinC, INPUT);
150152
}
151153

152154
// counter setup
@@ -162,11 +164,12 @@ void HallSensor::init(){
162164

163165
// function enabling hardware interrupts of the for the callback provided
164166
// if callback is not provided then the interrupt is not enabled
165-
void HallSensor::enableInterrupts(void (*doA)(), void(*doB)(), void(*doIndex)()){
167+
void HallSensor::enableInterrupts(void (*doA)(), void(*doB)(), void(*doC)()){
166168
// attach interrupt if functions provided
167169

168-
// A callback and B callback
170+
// A, B and C callback
169171
if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE);
170172
if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE);
173+
if(doC != nullptr) attachInterrupt(digitalPinToInterrupt(pinC), doC, CHANGE);
171174
}
172175

src/HallSensor.h

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -11,10 +11,11 @@ class HallSensor: public Sensor{
1111
HallSensor class constructor
1212
@param encA HallSensor B pin
1313
@param encB HallSensor B pin
14-
@param ppr impulses per rotation (cpr=ppr*4)
14+
@param encC HallSensor B pin
15+
@param pp pole pairs (e.g hoverboard motor has 15pp and small gimbals often have 7pp)
1516
@param index index pin number (optional input)
1617
*/
17-
HallSensor(int encA, int encB , float ppr, int index = 0);
18+
HallSensor(int encA, int encB, int encC, int pp);
1819

1920
/** HallSensor initialise pins */
2021
void init();
@@ -27,21 +28,21 @@ class HallSensor: public Sensor{
2728
* @param doIndex pointer to the Index channel interrupt handler function
2829
*
2930
*/
30-
void enableInterrupts(void (*doA)() = nullptr, void(*doB)() = nullptr, void(*doIndex)() = nullptr);
31+
void enableInterrupts(void (*doA)() = nullptr, void(*doB)() = nullptr, void(*doC)() = nullptr);
3132

3233
// HallSensor interrupt callback functions
3334
/** A channel callback function */
3435
void handleA();
3536
/** B channel callback function */
3637
void handleB();
37-
/** Index channel callback function */
38-
void handleIndex();
38+
/** C channel callback function */
39+
void handleC();
3940

4041

4142
// pins A and B
4243
int pinA; //!< HallSensor hardware pin A
4344
int pinB; //!< HallSensor hardware pin B
44-
int index_pin; //!< index pin
45+
int pinC; //!< index pin
4546

4647
// HallSensor configuration
4748
Pullup pullup; //!< Configuration parameter internal or external pullups
@@ -82,8 +83,7 @@ class HallSensor: public Sensor{
8283
volatile long pulse_timestamp;//!< last impulse timestamp in us
8384
volatile int A_active; //!< current active states of A channel
8485
volatile int B_active; //!< current active states of B channel
85-
volatile int I_active; //!< current active states of Index channel
86-
volatile long index_pulse_counter; //!< impulse counter number upon first index interrupt
86+
volatile int C_active; //!< current active states of Index channel
8787

8888
// velocity calculation variables
8989
float prev_Th, pulse_per_second;

0 commit comments

Comments
 (0)