Hi Owen,
It is what I did through the call of HandleA(), HandleB(), HandleC() in HallSensor::init(), to know the halls state.
Blockquote
#include “HallSensor.h”
/*
HallSensor(int hallA, int hallB , int cpr, int index)
- hallA, hallB, hallC - HallSensor A, B and C pins
- pp - pole pairs
*/
HallSensor::HallSensor(int _hallA, int _hallB, int _hallC, int _pp){
// HallSensor measurement structure init
// hardware pins
pinA = _hallA;
pinB = _hallB;
pinC = _hallC;
// counter setup
pulse_counter = 0;
pulse_timestamp = 0;
cpr = _pp * 6; // hall has 6 segments per electrical revolution
A_active = 0;
B_active = 0;
C_active = 0;
// velocity calculation variables
prev_pulse_counter = 0;
prev_timestamp_us = _micros();
// extern pullup as default
pullup = Pullup::EXTERN;
}
// HallSensor interrupt callback functions
// A channel
void HallSensor::handleA() {
A_active= digitalRead(pinA);
updateState();
}
// B channel
void HallSensor::handleB() {
B_active = digitalRead(pinB);
updateState();
}
// C channel
void HallSensor::handleC() {
C_active = digitalRead(pinC);
updateState();
}
// Determines whether the hallsensr state transition means that it has moved one step CW (+1), CCW (-1) or state transition is invalid (0)
// states are 3bits, one for each hall sensor
void HallSensor::updateState()
{
// here are expected state transitions (oldState > newState).
// CW state transitions are: ( 6 > 2 > 3 > 1 > 5 > 4 > 6 )
// CCW state transitions are: ( 6 > 4 > 5 > 1 > 3 > 2 > 6 )
// invalid state transitions are oldState == newState or if newState or oldState == 0 | 7 as hallsensors can’t be all on or all off
int rawDirection;
uint8_t newState = C_active + (B_active << 1) + (A_active << 2);
// Compute the distance (in terms of hall combination steps) between actual and last halls value
int8_t distance = HALLS_SEQ_120[newState] - HALLS_SEQ_120[state];
switch (distance)
{
case -5:
// Overflow sequence
if (HALLS_SEQ_120[newState] == 0)
{
pulse_counter ++;
rawDirection = Direction::CW;
}
break;
case -1:
pulse_counter --;
rawDirection = Direction::CCW;
break;
case 1:
pulse_counter ++;
rawDirection = Direction::CW;
break;
case 5:
// Underflow sequence
if (HALLS_SEQ_120[newState] == 5)
{
pulse_counter --;
rawDirection = Direction::CCW;
}
break;
default:
// If some steps has been lost or if Halls hasn't really changed or if it was just noise around transition,
// the sequence of halls is not correct, and therefore the system aborts the process.
rawDirection = Direction::UNKNOWN;
break;
}
state = newState;
direction = static_cast<Direction>(rawDirection * natural_direction);
pulse_timestamp = _micros();
}
/*
Shaft angle calculation
*/
float HallSensor::getAngle(){
long dN = pulse_counter - prev_pulse_counter;
if (dN != 0)
{
// time from last impulse
float Th = (pulse_timestamp - prev_timestamp_us) * 1e-6;
if (Th <= 0 || Th > 0.5)
Th = 1e-3;
// save variables for next pass
prev_timestamp_us = pulse_timestamp;
prev_pulse_counter = pulse_counter;
velocity = (float) _2PI * dN / (cpr * Th);
}
angle = (float) _2PI * pulse_counter / cpr;
return angle;
}
/*
Shaft velocity calculation
function using mixed time and frequency measurement technique
*/
float HallSensor::getVelocity(){
// this is calculated during the last call to getAngle();
return velocity;
}
// getter for index pin
// return -1 if no index
int HallSensor::needsAbsoluteZeroSearch(){
return 0;
}
// getter for index pin
int HallSensor::hasAbsoluteZero(){
return 0;
}
// initialize counter to zero
float HallSensor::initRelativeZero()
{
pulse_counter = 0;
pulse_timestamp = _micros();
velocity = 0;
return 0.0;
}
// initialize index to zero
float HallSensor::initAbsoluteZero(){
return 0.0;
}
// HallSensor initialisation of the hardware pins
// and calculation variables
void HallSensor::init(){
// HallSensor - check if pullup needed for your HallSensor
if(pullup == Pullup::INTERN){
pinMode(pinA, INPUT_PULLUP);
pinMode(pinB, INPUT_PULLUP);
pinMode(pinC, INPUT_PULLUP);
}else{
pinMode(pinA, INPUT);
pinMode(pinB, INPUT);
pinMode(pinC, INPUT);
}
state = 0;
handleA() ;
handleB() ;
handleC() ;
// counter setup
pulse_counter = 0;
pulse_timestamp = _micros();
prev_pulse_counter = 0;
prev_timestamp_us = _micros();
}
/*
Electrical angle calculation
*/
float HallSensor::getElecAngle(){
return (HALLS_SEQ_120[state] * 60-120) * (_PI/180);
}
// function enabling hardware interrupts for the callback provided
// if callback is not provided then the interrupt is not enabled
void HallSensor::enableInterrupts(void (*doA)(), void(*doB)(), void(*doC)()){
// attach interrupt if functions provided
// A, B and C callback
if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE);
if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE);
if(doC != nullptr) attachInterrupt(digitalPinToInterrupt(pinC), doC, CHANGE);
}