Hall effect Sensor (skip calibration)

@Marc_O i think there is some improvements that can be made in this area.

I have a question though - if the motor has not moved then none of the hall sensors interrupts will have been called and the state will be unknown. It is only after two hall commutations that the state becomes initialised.

Perhaps we could digitalRead() the three hall inputs on init to immediately know state but i suspect you can’t automatically know direction (i.e. if hall direction is same as motor direction).

My head hurts thinking about calibration! Part of what calibration does is to pull motor to a definite electrical angle and then compare this to what the sensor says, this gives us our zero offset so that FOC algorithm can place the magnetic field 90degrees ahead.

@Antun_Skuric can probably explain if there are any types of sensor that don’t need that first calibration. I think they all need it but i might be wrong.

Tldr: I don’t think your approach will generalise but I’m also suspecting that there is problem with the current approach.

Re. sharing files. You’ve attached an image of your code. You can paste code into a code block or if you have tested improvements then we welcome pull requests to simplefoc github repo.

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);
}

Sorry,
But it seems it doesn’t work well from my side the “block quote”.

From my side, it works well my modification of both files “HallSensor”, with my 8 poles motor.

I am going to try through GitHub :slight_smile:

Thanks

@Owen_Williams, @Antun_Skuric,

I put my code on gitHub.

Thank you in advance for your replies.

Hi,

I recently got a motor with encoder A/B and hall sensors. Has anyone tried managed to get a combination working? Looks like Marc has hall sensor only working?

Hi Jonathan,
Try this and tell me:

// align sensor and start FOC
#define _2PI_3 2.09439510239
#define _5PI_3 5.23598775598
#define _4PI_3 4.18879020478
const float HALLS_SEQ_120[8] = {-1,_PI,_PI_3,_2PI_3,_5PI_3,_4PI_3 ,0 ,-1};
int8_t st = (digitalRead(sensor.pinC)) + (digitalRead(sensor.pinB) << 1) + (digitalRead(sensor.pinA)<<2);
// align sensor and start FOC
motor.initFOC(HALLS_SEQ_120[st], Direction::CW);

Best regards

Hi @Marc_O. I looked at your code/pull request from a few weeks back. SimpleFOC 2.0 has a new hall implementation. It’s taken bits from what you did but I’ve made other changes to.

The original code and your code didn’t calibrate for all motors (mine worked for mine, yours worked for yours). I’m hoping the new code generalises a bit better, but i still think it isn’t perfect. I’ve also been trying get smother velocity readings, there is a commit on dev branch.

My belief with hall is that because hall resolution is poor (60 degrees electrical), that calibration will be correct to ±30 degrees or so. So a little bit of manual tweaking of calibration angle might be required. Without the calibration you might see difference in speed with same voltage when going in opposite direction (probably due to FOC field weakening)

@Jonathan_Robson blending hall and AB encoder sounds interesting! I think i would only use hall in setup() to determine electrical position and attach the encoder to motor class for accurate relative position.

Are you sure you encoder isnt abz? If it has zindex output, then i wouldn’t bother using hall as abz is likely to be superior.

Yes certainly A/B only, perhaps not that common, but no index.

Hi @Owen_Williams,
Thank you for your feedback, I confirm the new SimpleFOC 2.0 doesn’t work with my motor without calibration with halls from my side, but it works with 1.6.0 or 1.6.1 with the trick here above.
So, you are right the current code of SimpleFOC (and mine) is not perfect. And, I effectively agree with you about +/- 30°, because in sector 0 the rotor is between 30 degrees and 90 degrees, in sector 1, it is between 90 degrees and 120 degrees, in sector 2, it is between 120 and 180, and so on. If the motor is turning in positive direction the hall change match the lowest angle of the new sector (sector * 60 + 30) otherwise match the highest angle (sector * 60 + 90).
I am going to see what I can do for this automatically without calibration, because with (only) the Halls, it is not necessary to do a calibration versus others solutions (magnetic, relative, and so on), I am belief.
What motor do you use (reference) to do your tries ?
@Jonathan_Robson, you are effectively right and advised about to combine halls with any encoder that it be relative, magnetic or other. It clearly is more reliable, and to fix in real time the offset between them (It is what I do from my side).
By the way, it is common to use relative encoder with only A/B.
Have you tried the code here above ?
What motor do you use (reference) ?

Best Regards.

I have not, just received the motor, not sure if it’s worth trying simplefoc again.

Btw, the correct way to use hall sensors and encoder together is to do a single calibration in both directions and find out how far(encoder steps) the rising edge of one of the hall sensors are to the motor D/Q axis, same as an encoder index calibration. This allows you to use the hall sensor for startup commutation but as soon as the rising edge is picked up in whichever direction the calibrated offset is applied and you can apply FOC correctly.

1 Like

Hi @Owen_Williams, @Jonathan_Robson,
@Owen_Williams I have carried out a few tries, and now my motor works with SimpleFOC V2.0 with the halls. In fact, the polarity of Halls are not the same than yours, it is for it that didn’t work with your sequence:
// seq 1 > 5 > 4 > 6 > 2 > 3 > 1 000 001 010 011 100 101 110 111
const int8_t ELECTRIC_SECTORS[8] = { -1, 0, 4, 5, 2, 1, 3 , -1 };
and mine:
// Relative order of the commutation based on the Halls value [000 001 010 011 100 101 110 111]
const int8_t ELECTRIC_SECTORS_120[8] = {-1,5,3,4,1,0,2,-1};

So, I have modified the update() function under “HallSensor.cpp” like this:
/* Apply polarity */
if (hall_polarity)
/* Reverse from H3H2H1 to H1H2H3 */
hall_state = C_active + (B_active << 1) + (A_active << 2);
else
hall_state = A_active + (B_active << 1) + (C_active << 2);
and the instance:
// hall sensor instance
HallSensor sensor = HallSensor(H1, H2, H3, POL, PP);
With POL = 0 for me.
And now, that works…remains now to the start automatically, without calibration…

Could you try from your side, please ? and tell me, what motor do you use (reference + halls) to do your tries ?

Best regards.

@Marc_O this is where I’m hoping natural direction detection helps out. I’d expect changing second arg of motor.initFOC(ang, Direction::CCW) would be equivalent.

If it doesn’t work then we need to work out why and try to get it to work!

Hi @Owen_Williams,
I have replaced your sequence by this one in HallSensors.h:
const int8_t ELECTRIC_SECTORS[8] = {-1,5,3,4,1,0,2,-1};
and I put this in the main.cpp:
motor.setPhaseVoltage(motor.voltage_sensor_align, 0, _3PI_2);
motor.initFOC(_3PI_2, Direction::CW);
or this:
motor.initFOC()

There only is this configuration it worked with SimpleFOC 2.0 and several standard motors with Hall sensors from my side.
It only is this sequence which works from my side.

I don’t hide I understand nothing for the moment what can happen, and what is the difference with you (???)

it can be due to the sequence start at a fix value reference at 0° mechanical versus electrical angle…

@Marc_O - I’ve spotted and fixed a bug in the hall sensor that only happens if sensor_direction is CCW. So there is a 50% chance of being affected and if you are affected it mostly affects angle control mode I think. The change is on the dev branch.

I’m hoping this will mean that hall sensors behave better for all now. The 3x Halls sensors can be arranged in 6 ways but when you look at a repeating sequence of commutations there are only two permutations (ABC and CBA).

ABC - ABCabc
ACB - aCBAcb
BAC - baCBAc
BCA - bcABCa
CAB - cABCab
CBA - CBAcba

To test my fix - I tried switching hall A for C (which should have put me on the other CBA permutation). The only thing I noticed was that the sensor_direction changed. Similarly if I change the motor phase leads A and C I also see the sensor_direction changing. In all 4 motor/hall permutations I can automatically calibrate and movement is stable.

TLDR - I’m very much hoping that we’ve got a generalised hall sensor implementation and that your ‘polarity’ fix isn’t needed. I think your polarity was needed because of the CCW bug I fixed on dev. It it turns out we do need your polarity fix then a) I don’t understand hall sensors and b) we’ll have to find a way to detect polarity during calibration.

Your changes and persistence has really helped me improve the hall sensor implementation, thanks!

Hi @Owen_Williams,
It sounds good now ! Good job ! I try your code and that works with an in runner standard motor 7PP, and an out runner standard motor 4PP.

Before your modification, I had seen that the CCW was wrong because with negative velocity the current consumption was much superior versus CW, therefore the angle was shifted in this direction. But I would not know from where that came, because in modifying the code with the polarity and my sequence, that worked from my side.

I understand better now why from your side and from my side was different, therefore Well done ! To skip the calibration, and to start the motor, just to do now for example: motor.initFOC(sensor.electric_sector*_PI_3, Direction::CW);

For your information, I changed _micros() with a Timer for best accuracy (true count time of microsecond).

I had a question about from your callback (I am not expert in C++ like you), could you explain what it is a “call back” that you have put in Hallsensor.cpp, please ?

if (onSectorChange != nullptr) onSectorChange(electric_sector);

and 

void HallSensor::attachSectorCallback(void (*_onSectorChange)(int sector)) {
  onSectorChange = _onSectorChange;
}

Thank you in advance.

Good to hear that it is working better. The callback allows you to get notified when the hall changes sector. Your callback method (that you attach) will get called and will be passed the electrical sector that the hall has moved to.

Why is this useful? Apart from debugging, it could perhaps be used for very high speeds perhaps skipping the FOC maths and/or used with trapezoidal modulation.

Probably I can help a little to understand the different current consumption between CW and CCW.
This is very typical for Hall sensor commutation. Because every hall sensor has properties like hysteresis and sensitivity the ideal commutation point is not in the middle of a slot. The best commutation moves a little towards CW or CCW. Therefor the sensors are not placed in the geometrical middle but a little back. It is a little as moving the ignition point of a combustion engine.
If you change direction you get the double of that compensation angle as switching error. That leads to a reduced efficiency. You can see it as increased current consumptions for the same torque.

You can compensate it by changing the zero-angle when changing the direction. This ability for tuning is what makes SimpleFOC that candy.

Sorry to bump this old thread but I have one doubt.
If I understand correctly, during sensor align, SimpleFOC is setting a particular electrical angle, and then measuring the electric angle from the sensor, which is a whole sector with hall sensors.

I have been trying to implement something different in the hoverboard foc firmware based on what I learned from other firmwares, and I was wondering if there would be interest in this feature for simpleFOC.

  • initialize ELECTRIC_SECTORS array with -1 values
  • run the motor in openloop angle mode, move to 360 and back
  • average the angle for each hall position ( VESC averages sin and cos of the angle as it’s more difficult to average an angle that wraps around). This should give the middle electric angle for each sector and also gives the right ELECTRIC_SECTORS table but with angles instead of the sector number. It works better then identifying the edges of the sectors because of the cogging. The angle that should be used is the middle angle -30 or +30 depending on the direction.

In the current ELECTRIC_SECTORS array, position 0 and 7 are impossible because we assume the hall sensors are 120 degrees apart. This is not true with a 60 degrees hall sensor configuration. So with this method the -1 values are on other hall positions that are impossible with the 60 degree configuration.

One additional check I was doing is making sure each hall sensor state is changing during the calibration. Like MIN state <> MAX state for each hall sensor, to identify hall sensors that are defective.

Hey, that’s interesting!!

It sounds like it would be beneficial to persons using Hall Sensors.

In terms of the code, I think it would need changes to the initialization - something that’s been on the TODO list.

I think the way forward would be to separate out the initialization code from the motor class, e.g. the work done in initFOC(). And keep the default behavior as “DefaultInitialization”, but enable you to replace it, something like motor.initialization = new OpenLoopAverageInitialization();