SmoothingSensor: Experimental sensor angle extrapoltion

I was going to give this a spin soon. I seem to recall that this was now in the main branch, so no need to use the dev branch?

So I include smoothingsensor.h as mentioned above, instantiate the hall sensors in the usual way (maybe give them a test or do the motor init first) and then instantiate the smoothingsensor, feeding it the hall sensor object. Then feed the motor object the smoothingsensor object so it uses that instead of using the hall object directly. Do I need to tell smoothingsensor the time constant for the filter or something?

Hm. Seems like I might encounter difficulty with the motor initialization routine, where it detects the pinouts and orientation of the hall sensors if it was trying to use the smoothingsensor object for that. I can probably skip that part though. I think my motor probably has well aligned hall sensors and I just gotta make sure I don’t get the wiring wrong.

That is correct. SmoothingSensor doesn’t have any filter constants, but you do need to set phase_correction = -_PI_6 for hall sensors. And it doesn’t have any state variables that need continuous updating, so you can call motor.linkSensor at any time to switch between using the HallSensor directly and going through the SmoothingSensor.

I don’t think it will interfere with calibration since the motor velocity should be zero at the time. But the calibration procedure doesn’t really work for hall sensors anyway unless you’re using trapezoid120 modulation. You have to manually tune the zero_electric_angle until top speed is the same in both directions.

I did that with hoverboard motors under no_load condition and it worked fine, but will that work with a fan?
Maybe @Anthony_Douglas has to cover the blades to avoid airflow…

1 Like

Good point. I’m not sure how to find the ideal zero angle then. Might need to write a better calibration routine.

For a fan it would depend on the type - many operate in one direction only and have their design optimized for pushing air one way. Others are bidirectional and designed symmetrically…

As an alternative to tuning the zero by going both directions you can also tune it going only one direction and watching for minimum current, I guess.

2 Likes

I can take the fan blades off, but what I did previously with the magnetic angle sensor was get it to go in one direction, then the other, and assume the reality was half way in between. I.e. the lag of the angle sensor’s reading of the rotor position is X degrees behind the electrical angle during slow, high current open loop motion (sine wave commutation) and Y degrees behind when rotating in the other direction. Assume the same small but not insignificant load in both directions. Thus, the real lag is equal in both directions. So we take the difference between X and Y and divide by two. That’s the bias of the sensor relative to the actual rotor position.

For the magnetic angle sensor I measured it all the way around with a pico but that ended up being really complicated. Hopefully my motor is a little better built than that, I doubt there is significant assymetry in the alignment of the halls. They seem to be pretty good quality motors.

This complication concerns me, though, I thought the halls were expected to just clocked in fairly accurately at the right positions. The motor seems to work pretty well and about the same in both directions with a “dumb” hall sensor based motor driver that I got on amazon.

I only tested a few almost identical motors, but they were all at 0 degree after init.
Maybe we make up problems where they don’t exist.

1 Like

There is a lot of stuff and uncertainty still, I want to try this, but there is so much that can go wrong and so much uncertainty it seems naive to think I’ll be able to get it to work at this point without some example code. I’m not even clear which branch I need to use any more.

Can we have some example code?

I have this torque mode driver working, using the QVADRANS:

‘’’
/**
*

  • Torque control example using voltage control loop.
  • Most of the low-end BLDC driver boards doesn’t have current measurement therefore SimpleFOC offers
  • you a way to control motor torque by setting the voltage to the motor instead of the current.
  • This makes the BLDC motor effectively a DC motor, and you can use it in a same way.
    */
    #define polepairs 11
    #include <Arduino.h>
    #include <SimpleFOC.h>
    #include <smoothingsensor.h>
    BLDCMotor motor = BLDCMotor(polepairs);
    BLDCDriver6PWM driver = BLDCDriver6PWM(PA8, PB13, PA9, PB14, PA10, PB15);
    // hall sensor instance
    HallSensor sensor = HallSensor(PC6, PB11, PA3, polepairs);

// Interrupt routine intialisation
// channel A and B callbacks
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
void doC(){sensor.handleC();}

// voltage set point variable
float target_voltage = 2;

void setup() {
pinMode(PC6, INPUT_PULLUP); // LED_BUILTIN
pinMode(PB11, INPUT_PULLUP);
pinMode(PA3, INPUT_PULLUP);
Serial.begin(115200);
// enable more verbose output for debugging
// comment out if not needed
SimpleFOCDebug::enable(&Serial);

// initialize encoder sensor hardware
sensor.init();
sensor.enableInterrupts(doA, doB, doC);
// link the motor to the sensor
motor.linkSensor(&sensor);

// driver config
// power supply voltage [V]
driver.voltage_power_supply = 24;
driver.init();
// link driver
motor.linkDriver(&driver);

// aligning voltage
motor.voltage_sensor_align = 3;

// choose FOC modulation (optional)
motor.foc_modulation = FOCModulationType::SinePWM;

// set motion control loop to be used
motor.controller = MotionControlType::torque;
// initialize motor
motor.init();
// align sensor and start FOC
motor.initFOC();

}

void loop() {

// main FOC algorithm function
// the faster you run this function the better
// Arduino UNO loop ~1kHz
// Bluepill loop ~10kHz
motor.loopFOC();

// Motion control function
// velocity, position or voltage (defined in motor.controller)
// this function can be run at much lower frequency than loopFOC() function
// You can also use motor.move() and set the motor.target in the code
motor.move(target_voltage);
}
‘’’

1 Like

I wish I would have realized this sooner… there’s an easy way to automate the setting of phase_correction. Just add a second constructor specialized for HallSensor:

SmoothingSensor::SmoothingSensor(HallSensor& s, const FOCMotor& m) : _wrapped(s), _motor(m) {
  phase_correction = -_PI_6;
}
2 Likes

So that line goes directly below the instantation of the smoothingsensor object, dekutree?

No, it’s a potential edit to the SmoothingSensor class to make it more user-friendly. Just set the phase correction as in the example Candas1 linked for now.

SmoothingSensor is super simple to use. There really are only 3 relevant lines. Declaration of the SmoothingSensor, setting phase correction, and passing it to motor.linkSensor.

1 Like

This is amazing. I folded together my simple known to work with this hardware example code with the essential elements for the smoothingsensor in the file Candas1 posted. Here is the result. I cannot get a potentiometer to read on the QVADRANS so I have to ramp the voltage up to avoid jerking on startup.

The commander would be something I should figure out of course, but I chopped out the velocity mode stuff because I want to keep it as elemental as possible. Block by block building forward. the commander and the velocity mode PID control stuff is additional components to be gotten working and integrated later if desired.

’ ’ ’
/**
*

  • Torque control example using voltage control loop.
  • Most of the low-end BLDC driver boards doesn’t have current measurement therefore SimpleFOC offers
  • you a way to control motor torque by setting the voltage to the motor instead of the current.
  • This makes the BLDC motor effectively a DC motor, and you can use it in a same way.
    */
    #define polepairs 11
    #define seconds_to_ramp

#include <Arduino.h>
#include <SimpleFOC.h>
#include <SimpleFOCDrivers.h>
#include <encoders/smoothing/SmoothingSensor.h>
BLDCMotor motor = BLDCMotor(polepairs);
BLDCDriver6PWM driver = BLDCDriver6PWM(PA8, PB13, PA9, PB14, PA10, PB15);
// hall sensor instance
HallSensor sensor = HallSensor(PC6, PB11, PA3, polepairs);
SmoothingSensor smooth(sensor, motor);

// Interrupt routine intialisation
// channel A and B callbacks
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
void doC(){sensor.handleC();}

// voltage set point variable
float target_voltage = 17;

void setup() {
pinMode(PC6, INPUT_PULLUP); // LED_BUILTIN
pinMode(PB11, INPUT_PULLUP);
pinMode(PA3, INPUT_PULLUP);
smooth.phase_correction = -_PI_6;
Serial.begin(115200);
// enable more verbose output for debugging
// comment out if not needed
// SimpleFOCDebug::enable(&Serial);

// initialize encoder sensor hardware
sensor.init();
sensor.enableInterrupts(doA, doB, doC);
// link the motor to the sensor
motor.linkSensor(&smooth);

// driver config
// power supply voltage [V]
driver.voltage_power_supply = 24;
driver.init();
// link driver
motor.linkDriver(&driver);

// aligning voltage
motor.voltage_sensor_align = 5;

// choose FOC modulation (optional)
motor.foc_modulation = FOCModulationType::SinePWM;

// set motion control loop to be used
motor.controller = MotionControlType::torque;
// initialize motor
motor.init();
// align sensor and start FOC
motor.initFOC();
for (float i = 0.0f; i < 600000.0f; i++){// assume 33 khz is what motor.loopfoc runs at if looped so 0.03 msec per loop so 600,000 should be 18 sec
motor.loopFOC();
motor.move(i*target_voltage/600000);
}
}

void loop() {

// main FOC algorithm function
// the faster you run this function the better
// Arduino UNO loop ~1kHz
// Bluepill loop ~10kHz
motor.loopFOC();

// Motion control function
// velocity, position or voltage (defined in motor.controller)
// this function can be run at much lower frequency than loopFOC() function
// You can also use motor.move() and set the motor.target in the code
motor.move(target_voltage);
}
’ ’ ’

I thought it would take a long time to get this working so I’m very grateful for the help, thanks guys, I promise to pay it forward by advancing the successor to the qvadrans (me and the guy who got that ball rolling decided for complicated reasons we should fork it and disconnect it from the past). Including by sending out free boards to people and stuff.

I have noticed that it glitches out increasingly at more than about 200 rpm, it sounds like a hard drive seeking randomly, twitching the motor around the table.

The non-smoothing sensor version of the code, previously posted, seems to be ok in this regard. I also noticed it draws more current than it did. It draws more than 250 mA even when unloaded.

There may be some kind of issue with the phase delay or something? The glitching appears to be random, I will check to see if it goes away when the motor is loaded.

hm, it appears to be unaffected by loading, and too random to be a coding thing. It seems like somethng is poorly grounded or there is an electrical noise issue, probably something with the hardware. I have 10 kohm pullups on the hall sensors. poking around with my finger reveals nothing useful.

If your sensor direction is -1, make sure you have the latest SmoothingSensor (master and dev branch are the same, last change a year ago). The original version only worked in positive direction, but Candas1 fixed it.

Try commenting out the line sensor.enableInterrupts(doA, doB, doC);
Thanks to Candas1 again, HallSensor no longer requires interrupts, and sometimes works better without them (bouncy sensor signals trigger multiple interrupts, whereas sampling once per frame generally skips over any brief moment of bouncing). The only drawback is slightly less accurate velocity readings, but the lowpass filter smooths it out.

1 Like

I tried commenting that line out, updating (it was already 1.0.8 version for the simpleFOC drivers and 2.3.4 for SimpleFOC but I removed and reinstalled to be sure). I also tried making the pullups 4.7 k instead of 10 k.

Commenting out that line makes it about four times worse, but the other stuff made no diff. Seems like it’s gotta be some kind of noise or bouncing around, maybe a noise issue in the QVADRANS even.

Hm, putting 3.9 nanofarad capacitors on the connector for the hall sensor (not the optimal place but accessible) reduced the issue enough that I can use the system at least.