26 A_active= digitalRead(
pinA);
31 B_active = digitalRead(
pinB);
37 C_active = digitalRead(
pinC);
44 void HallSensor::updateState() {
45 long new_pulse_timestamp =
_micros();
47 int8_t new_hall_state = C_active + (B_active << 1) + (A_active << 2);
73 pulse_diff = new_pulse_timestamp - pulse_timestamp;
78 pulse_timestamp = new_pulse_timestamp;
92 onSectorChange = _onSectorChange;
107 if (pulse_diff == 0 || ((
_micros() - pulse_timestamp) > pulse_diff) ) {
123 pinMode(
pinA, INPUT_PULLUP);
124 pinMode(
pinB, INPUT_PULLUP);
125 pinMode(
pinC, INPUT_PULLUP);
127 pinMode(
pinA, INPUT);
128 pinMode(
pinB, INPUT);
129 pinMode(
pinC, INPUT);
133 A_active= digitalRead(
pinA);
134 B_active = digitalRead(
pinB);
135 C_active = digitalRead(
pinC);
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);