2
2
3
3
4
4
/*
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
9
8
*/
10
9
11
- HallSensor::HallSensor (int _encA , int _encB , float _ppr , int _index ){
10
+ HallSensor::HallSensor (int _hallA , int _hallB, int _hallC , int _pp ){
12
11
13
12
// HallSensor measurement structure init
14
13
// hardware pins
15
- pinA = _encA;
16
- pinB = _encB;
14
+ pinA = _hallA;
15
+ pinB = _hallB;
16
+ pinC = _hallC;
17
17
// counter setup
18
18
pulse_counter = 0 ;
19
19
pulse_timestamp = 0 ;
20
20
21
- cpr = _ppr;
21
+ cpr = _pp * 6 ; // hall has 6 segments per electrical revolution
22
22
A_active = 0 ;
23
23
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 ;
28
25
29
26
// velocity calculation variables
30
27
prev_Th = 0 ;
@@ -34,7 +31,6 @@ HallSensor::HallSensor(int _encA, int _encB , float _ppr, int _index){
34
31
35
32
// extern pullup as default
36
33
pullup = Pullup::EXTERN;
37
- // enable quadrature HallSensor by default
38
34
39
35
}
40
36
@@ -61,6 +57,18 @@ void HallSensor::handleB() {
61
57
62
58
}
63
59
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
+
64
72
/*
65
73
Shaft angle calculation
66
74
*/
@@ -109,31 +117,25 @@ float HallSensor::getVelocity(){
109
117
// getter for index pin
110
118
// return -1 if no index
111
119
int HallSensor::needsAbsoluteZeroSearch (){
112
- return index_pulse_counter == 0 ;
120
+ return 0 ;
113
121
}
114
122
// getter for index pin
115
123
int HallSensor::hasAbsoluteZero (){
116
- return hasIndex () ;
124
+ return 0 ;
117
125
}
118
126
// initialize counter to zero
119
127
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 ;
124
129
}
125
130
// initialize index to zero
126
131
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 ;
130
133
}
131
134
// private function used to determine if HallSensor has index
132
135
int HallSensor::hasIndex (){
133
- return index_pin != 0 ;
136
+ return 0 ;
134
137
}
135
138
136
-
137
139
// HallSensor initialisation of the hardware pins
138
140
// and calculation variables
139
141
void HallSensor::init (){
@@ -142,11 +144,11 @@ void HallSensor::init(){
142
144
if (pullup == Pullup::INTERN){
143
145
pinMode (pinA, INPUT_PULLUP);
144
146
pinMode (pinB, INPUT_PULLUP);
145
- if ( hasIndex ()) pinMode (index_pin, INPUT_PULLUP);
147
+ pinMode (pinC, INPUT_PULLUP);
146
148
}else {
147
149
pinMode (pinA, INPUT);
148
150
pinMode (pinB, INPUT);
149
- if ( hasIndex ()) pinMode (index_pin, INPUT);
151
+ pinMode (pinC, INPUT);
150
152
}
151
153
152
154
// counter setup
@@ -162,11 +164,12 @@ void HallSensor::init(){
162
164
163
165
// function enabling hardware interrupts of the for the callback provided
164
166
// 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 )()){
166
168
// attach interrupt if functions provided
167
169
168
- // A callback and B callback
170
+ // A, B and C callback
169
171
if (doA != nullptr ) attachInterrupt (digitalPinToInterrupt (pinA), doA, CHANGE);
170
172
if (doB != nullptr ) attachInterrupt (digitalPinToInterrupt (pinB), doB, CHANGE);
173
+ if (doC != nullptr ) attachInterrupt (digitalPinToInterrupt (pinC), doC, CHANGE);
171
174
}
172
175
0 commit comments