Skip to content

Commit

Permalink
Merge pull request #424 from Candas1/hall_no_interrupt
Browse files Browse the repository at this point in the history
Hall sensor without interrupt
  • Loading branch information
runger1101001 authored Jul 19, 2024
2 parents c27bc4b + d7d4488 commit 31ed492
Show file tree
Hide file tree
Showing 2 changed files with 20 additions and 10 deletions.
29 changes: 19 additions & 10 deletions src/sensors/HallSensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,22 +42,21 @@ void HallSensor::handleC() {
* Updates the state and sector following an interrupt
*/
void HallSensor::updateState() {
long new_pulse_timestamp = _micros();

int8_t new_hall_state = C_active + (B_active << 1) + (A_active << 2);

// glitch avoidance #1 - sometimes we get an interrupt but pins haven't changed
if (new_hall_state == hall_state) {
return;
}
if (new_hall_state == hall_state) return;

long new_pulse_timestamp = _micros();
hall_state = new_hall_state;

int8_t new_electric_sector = ELECTRIC_SECTORS[hall_state];
if (new_electric_sector - electric_sector > 3) {
int8_t electric_sector_dif = new_electric_sector - electric_sector;
if (electric_sector_dif > 3) {
//underflow
direction = Direction::CCW;
electric_rotations += direction;
} else if (new_electric_sector - electric_sector < (-3)) {
} else if (electric_sector_dif < (-3)) {
//overflow
direction = Direction::CW;
electric_rotations += direction;
Expand Down Expand Up @@ -96,11 +95,19 @@ void HallSensor::attachSectorCallback(void (*_onSectorChange)(int sector)) {
// Sensor update function. Safely copy volatile interrupt variables into Sensor base class state variables.
void HallSensor::update() {
// Copy volatile variables in minimal-duration blocking section to ensure no interrupts are missed
noInterrupts();
if (use_interrupt){
noInterrupts();
}else{
A_active = digitalRead(pinA);
B_active = digitalRead(pinB);
C_active = digitalRead(pinC);
updateState();
}

angle_prev_ts = pulse_timestamp;
long last_electric_rotations = electric_rotations;
int8_t last_electric_sector = electric_sector;
interrupts();
if (use_interrupt) interrupts();
angle_prev = ((float)((last_electric_rotations * 6 + last_electric_sector) % cpr) / (float)cpr) * _2PI ;
full_rotations = (int32_t)((last_electric_rotations * 6 + last_electric_sector) / cpr);
}
Expand Down Expand Up @@ -150,7 +157,7 @@ void HallSensor::init(){
}

// init hall_state
A_active= digitalRead(pinA);
A_active = digitalRead(pinA);
B_active = digitalRead(pinB);
C_active = digitalRead(pinC);
updateState();
Expand All @@ -169,4 +176,6 @@ void HallSensor::enableInterrupts(void (*doA)(), void(*doB)(), void(*doC)()){
if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE);
if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE);
if(doC != nullptr) attachInterrupt(digitalPinToInterrupt(pinC), doC, CHANGE);

use_interrupt = true;
}
1 change: 1 addition & 0 deletions src/sensors/HallSensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@ class HallSensor: public Sensor{
int pinA; //!< HallSensor hardware pin A
int pinB; //!< HallSensor hardware pin B
int pinC; //!< HallSensor hardware pin C
int use_interrupt; //!< True if interrupts have been attached

// HallSensor configuration
Pullup pullup; //!< Configuration parameter internal or external pullups
Expand Down

0 comments on commit 31ed492

Please sign in to comment.