26 A_active= digitalRead(
pinA);
31 B_active = digitalRead(
pinB);
37 C_active = digitalRead(
pinC);
44void HallSensor::updateState() {
45 int8_t new_hall_state = C_active + (B_active << 1) + (A_active << 2);
50 long new_pulse_timestamp =
_micros();
55 if (electric_sector_dif > 3) {
59 }
else if (electric_sector_dif < (-3)) {
71 pulse_diff = new_pulse_timestamp - pulse_timestamp;
76 pulse_timestamp = new_pulse_timestamp;
90 onSectorChange = _onSectorChange;
101 A_active = digitalRead(
pinA);
102 B_active = digitalRead(
pinB);
103 C_active = digitalRead(
pinC);
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);
131 long last_pulse_timestamp = pulse_timestamp;
132 long last_pulse_diff = pulse_diff;
134 if (last_pulse_diff == 0 || ((
long)(
_micros() - last_pulse_timestamp) > last_pulse_diff*2) ) {
150 pinMode(
pinA, INPUT_PULLUP);
151 pinMode(
pinB, INPUT_PULLUP);
152 pinMode(
pinC, INPUT_PULLUP);
160 A_active = digitalRead(
pinA);
161 B_active = digitalRead(
pinB);
162 C_active = digitalRead(
pinC);
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);
const int8_t ELECTRIC_SECTORS[8]
@ USE_EXTERN
Use external pullups.
@ USE_INTERN
Use internal pullups.
volatile int8_t electric_sector
HallSensor(int encA, int encB, int encC, int pp)
int cpr
HallSensor cpr number.
int pinB
HallSensor hardware pin B.
int use_interrupt
True if interrupts have been attached.
void attachSectorCallback(void(*onSectorChange)(int a)=nullptr)
float getVelocity() override
float getSensorAngle() override
volatile long total_interrupts
void enableInterrupts(void(*doA)()=nullptr, void(*doB)()=nullptr, void(*doC)()=nullptr)
volatile long electric_rotations
int pinC
HallSensor hardware pin C.
Pullup pullup
Configuration parameter internal or external pullups.
int pinA
HallSensor hardware pin A.
volatile int8_t hall_state