Noisy velocity readings in open loop and inconsistent pole pair calculations

I’m using a ROB-20441 motor from sparkfun driven in 6PWM mode by a TMC 6300 running on a STM32G474RE, with an AS5047P magnetic sensor. I’m powering the AS5047P with 3v3 from the G474, and have the jumper and resistors configured for 3v3.
I have been running it in velocity open loop, and get motion. For my application, I need to be able to achieve a steady 15Hz rotational frequency (94.2 rad/s rotational velocity).
Regular monitoring of the angular position of the motor and verification of the rotational velocity is needed. Currently, the velocity output is rather noisy.
The velocity output can be cleaned up significantly by only updating the sensor and calling sensor.getVelocity() every 1000 loops, but it’s still not a useful value (eg when set to 94.2 rad/s, the velocity is reported as anywhere from 20-70 with occasional -200s).
I am using the built-in ring magnet on the ROB-20441 and it is approximately 1mm from the AS5047P, so there should be sufficient magnetic field strength for the sensor.

Here is an example of the readings from the sensor while the motor is stationary:

position velocity
5.43 2.12
5.50 3.50
5.45 -2.72
5.46 0.85
5.50 1.61
5.45 -2.12
5.41 -2.31
5.43 1.14
5.43 0.23
5.54 5.33
5.39 -7.42
5.37 -1.03
5.61 11.80
5.42 -9.16

Here is the velocity open loop code I’ve been tinkering with:

#include <SimpleFOC.h>

BLDCMotor motor = BLDCMotor(4);
BLDCDriver6PWM driver = BLDCDriver6PWM(PA8, PB13, PA9, PB14, PA10, PB15);
MagneticSensorSPI sensor = MagneticSensorSPI(PA4, 14, 0x3FFF);

SPIClass SPI_1(PB5, PB4, PB3);

int i_max = 5000;
int i = 0;
int a_max = 50;
int a = 0;
int l = 0;

float target_velocity = 50;

void setup() {

  // driver config
  driver.voltage_power_supply = 9;
  driver.voltage_limit = 7.4;
  driver.pwm_frequency = 20000;
  // dead_zone [0,1] =  default 0.02 - 2%
  driver.dead_zone = 0.02;
  driver.init();
  // link the motor and the driver
  motor.linkDriver(&driver);

  // Magnetic Sensor
  sensor.init(&SPI_1);

  motor.linkSensor(&sensor);

  motor.voltage_limit = 7.4;

  motor.foc_modulation = FOCModulationType::SinePWM;
 
  // open loop control config
  motor.controller = MotionControlType::velocity_openloop;

  // init motor hardware
  motor.init();

  Serial.begin(115200);
  Serial.println("Motor ready!");
  Serial.println("Target velocity set to: ");
  Serial.print(target_velocity);
  
  _delay(2500);
}

void loop() {
  //sensor polling downsample
  if (l % 1000 == 0) {
    sensor.update();
    Serial.print(sensor.getMechanicalAngle());
    Serial.print("\t");
    Serial.print(sensor.getVelocity());
    Serial.print("\n");
  }
  l++;

  //slow ramp in velocity
  if (i % (i_max / a_max) == 0 && a < a_max) {
    a++;
  }
  i++;
  
  motor.move(a*(target_velocity / a_max));
}

What additional filtering or changes would you suggest I make to help my configuration run better?

I imagine that velocity closed loop operation would be produce a more steady output, but I haven’t been able to get even the torque control closed loop example to work.
One issue that might be contributing to torque control not working is that I am unsure of the number of pole pairs in this motor. The datasheet from Sparkfun is rather sparse but does indicate that there are 8 poles (so 4 pole pairs), but from what I’ve gathered this would an unusual configuration.
I have tested open loop function and the utility sketches with various pole pair values set (4-11), and haven’t noticed improved performance with any one particular setting.

The sensor, while a bit noisy when updated frequently, appears to be tracking position fine and reports an increase in angle of 2Pi when I turn the motor by hand by a full revolution.
However, when I run the ‘find_pole_pairs_number.ino’ example sketch, it turns by about 120 degrees in one direction, then about 30 degrees in either direction, then snaps to a nearby position and starts vibrating.
The number of pole pairs estimated by the sketch varies widely from 4 to 11.
Similarly, the ‘find_sensor_offset_and_direction.ino’ example sketch calculates a different sensor offset each time I run it.
When running the ‘find_kv_rating.ino’ example, it fails pole pair check and then starts oscillating about a fixed position, giving wildly varying kv values.

I’ve also done some reading on the current sensing implementation in SimpleFOC, and while I should be able to implement it in this setup (TMC 6300 breakout board I am using has a current sensing pin), I don’t quite understand how to wire it based on the descriptions in the wiki.
In the examples on the wiki it appears the analog pins are being used, but what are they connected to?
Additionally, I am not sure what the winding configuration of the motor is (wye vs delta) and so cannot determine the phase resistance.

Sorry for so many questions, I’m feeling a bit out of my depth. If you could use any additional information, please don’t hesitate to ask. I’ll take all the help I can get, in any of these areas!

I don’t know the motor, but it might be a motor with too much magnet cogging? These are hard to init and their readings vary a lot, just as you experienced.
The other reason for those variations, I can think of, is motor voltage too high while initializing.
Open loop tests require very low motor voltage, like 1V or less.
Furthermore you can’t init the sensor while the motor isn’t running free.

PS: You can try to find out the polepair number by guiding a needle pin around the motor.
If you’re lucky it is attracted to the inner magnets at certain points. Count the number of attraction points, it’s identical to your magnet count.
8 magnets are not so unusual as you might think.

Hello,

I tested this motor in “velocity_openloop” mode with SimpleFOCMini and an RP2040-Zero ==> 4 pole-pairs.
it works well at 200 Rad/s.
My Arduino stetch for this test:

#include <Arduino.h>
#include <SimpleFOC.h>

#define OUT1 12 // pin out1
#define OUT2 11 // pin out2
#define OUT3 10 // pin out3
#define MOTOR_ENABLE 9 // pin enable
#define POLE_NB 4 // 8 poles == 4 pole-pairs

// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(POLE_NB); // Nombre de pôles du moteur
BLDCDriver3PWM driver = BLDCDriver3PWM(OUT1, OUT2, OUT3, MOTOR_ENABLE); // 3 phases + enable

Commander command = Commander(Serial);// instantiate the commander
void doMotor(char* cmd) {
  command.motor(&motor, cmd); // SimpleFOCStudio
}

//▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬setup▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬
void setup() {
  Serial.begin(115200); // use monitoring with serial
  delay(1500);

  command.add('M', doMotor, "motor");
  command.decimal_places = 4; // default 3 (moi 4)

  // tell the motor to use the monitoring
  motor.useMonitoring(Serial);
  motor.monitor_downsample = 0; // 0 = disable monitor at first - optional

  //▬▬▬▬▬▬▬▬▬▬▬▬Debug▬▬▬▬▬▬▬▬▬▬▬▬
  //SimpleFOCDebug::enable();
  SimpleFOCDebug::enable(&Serial);

  //▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬driver_config▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬
  driver.voltage_power_supply = 8.0f; // power supply voltage [V]
  driver.voltage_limit = 7.4f; // Max DC voltage allowed
  driver.pwm_frequency = 66000; // 24000  66000 // pwm frequency to be used [Hz]
  if (driver.init())  Serial.println("Driver init success!"); // init driver
  else {
    Serial.println("Driver init failed!");
    return;
  }
  motor.controller = MotionControlType::velocity_openloop; // velocity_openloop
  motor.linkDriver(&driver);  // link the motor and the driver

  // velocity PI controller
  motor.PID_velocity.P = 1.0f; // 0.2f 0.8f
  motor.PID_velocity.I = 20.0f; // 20
  motor.PID_velocity.D = 0.001f; // 0.001 / 0
  //motor.PID_velocity.output_ramp = 1000.0f; // 1000
  motor.LPF_velocity.Tf = 0.0001f; // 0.01f

  motor.velocity_limit = 20.0f; // rad/s
  motor.voltage_limit = 7.4f; // Rated Voltage 7.4V DC [Volts] // [V] - if phase resistance not defined
  motor.current_limit = 0.8f; //  At 7.4V 0.8 (max.1.0)A [Amp]
  //motor.phase_resistance = 8.0f; //
  motor.KV_rating = 270.0f; // rpm/volt - default not set

  //motor.useMonitoring(Serial); // https://docs.simplefoc.com/monitoring  // tell the motor to use the monitoring
  motor.monitor_variables =  _MON_TARGET | _MON_CURR_Q | _MON_CURR_D;
  motor.monitor_downsample = 0; // default 10 // 0 = disable monitor at first - optional

  motor.init(); // initialize motor
  motor.target = 0;  // set the inital  value
  _delay(1000);

} // End_setup

int count_move = 0;
void loop() {
  if (count_move < 200) {
    ++count_move;
    motor.target = count_move;
    _delay(1);
  }
  motor.move();
  command.run();
} // End_loop

Thank you for taking the time to reply, I really appreciate it! This model motor was used for the SmartKnob project which utilizes SimpleFOC, where it was selected because it has very little motor cogging. Still, I will try initializing with a lower voltage and see if it helps reduce the variation.

What do you mean by “you can’t init the sensor while the motor isn’t running free”? Do you mean it can’t be initialized in the software while the motor has any torque, so it should be initialized before the motor is?

Thanks for the tip about the polepairs! I will try it out.

Thanks for the reply! I appreciate the information, I’m glad to hear that somebody has had success with this motor at high speeds. I’ve been quite happy with how it runs in open loop mode–its very smooth, and it seems like its been able to achieve the speeds I need from it. The larger issue has been getting the AS5047P sensor to accurately/steadily read out the angular velocity to verify that it is running at the commanded speed. I’m at the point where I’m considering just attaching an optical chopper to it to verify the rotation, but that defeats the purpose of having a magnetometer.

I notice in your sketch you attached that you specify PID values for the velocity, I wasn’t aware that they would be useful in openloop mode since the sensor is not providing feedback. How are you verifying that the motor is actually running at 200 rad/s?

Thank you again for the reply!

Hey @nanotrav, looking at your code i have some tips although i am not sure about the exact source of the problem

  1. Try to use the motor monitoring functionality instead of the getVelocity(), it worked better for me, use high serial baud. Im just runnning 2 000 000 as it makes the loop faster and smoother. You can also downsample the motor monitoring in an easy way with motor.monitor_downsample.
  2. Try to use PID parameters for open loop, in the docs you have typical values listed in options cheat sheet. There is also a software Low Pass Filter for velocity (and other parameters) implemented in the lib. It might also help a bit.
  3. If you use openloop, the driver estimates the control parameters from the known motor parameters. Phase resistance and motor KV are essential for the driver to do it properly. There is a ready program in the library examples in ArduinoIDE to find the motor KV.
  4. Also look up the “Getting Started” chapter in the docs, there might be something usefull there.

Just some tips becouse it is hard to determine what it actually is. Maybe the driver needs more parameters and that is driving the control a bit nuts, and maybe your reading is just noisy becouse of the sensor or the way it is connected to the mcu. I had noisy readings on my hall sensors but it was a matter of a proper connection and some low pass filters.

Hi @Lambert14, I’ll try increasing the serial baud, thanks for the tip. Do you know how the motor monitoring functionality determines the angular position/velocity if it is not taking input from the magnetometer? My concern is that if it is just giving expected/calculated values, I’m not sure how to verify that they accurately reflect the motion if not by using a sensor (which brings me back to the problem of the sensor seeming unreliable).

Hey @nanotrav ,

A few points:

  • you should update the sensor more often, maybe once every loop iteration
  • you should call getVelocity() less often, maybe once every 4-20 loop iterations
  • updating it only every 1000th iteration is probably a bit too slow
  • in open loop mode, you can add a small delay to the loop, maybe 50-100 microseconds
  • you can pass the velocity values through our low pass filter class (this is what happens if you use the motor monitoring, it is outputting the motor.shaft_velocity, which is filtered. But in open loop this is a calculated value, not the sensor value).

But generally speaking we can see that for the “stationary” motor, the position values are jumping around a lot.
This can be an indication of weak magnetic field (you can check it by reading the magnitude register from the sensor, use our AS5047A driver class from the drivers repository…
It can also be the case that there is interference, either magnetic, from the motor itself, or electric interference. I would expect the electrical interference to cause random errors (also high bits) and not just error in the lower bits of the result.
Another kind of electrical interference could be power supply noise. This could explain the low bit instability. Have you tried adding some extra capacitance to the sensor power inputs, or powering it from a separate power source than the motor?

Because the velocity signal is differentiated from the position signal, having an unstable position means the velocity will always be unstable…

Hi @runger ,

Thank you for taking the time to give such detailed suggestions! I really appreciate it. I’ll work through them and see what I come up with. Currently, I am powering the sensor from the Nucleo’s onboard 3V3 power, while the motor/driver are powered from an external power supply. However, they have a common ground. I have not tried adding capacitance to the sensor power input. I’ve attached a diagram of my current wiring, in case that is helpful.

One question: you suggest that I pass the velocity values through the low pass filter class, how do I accomplish this in open loop mode? Sorry if this is a simple question.

Thanks again for the advice!

Hi @runger and others,

I used the AS5047 driver class from SimpleFOCDrivers to read the magnitude. Depending on the angular position of the motor (which has the ring magnet producing the field attached to the spindle), the value reported by sensor.readMagnitude() varies from 80-100. How am I meant to interpret this value/determine if it is too low?

I think it seems very low. My sensor setups typically report somewhere around 4000-5000…

You can also read the diagnostic register and check the MAGL and MAGH fields:

AS5047Diagnostics diag = readDiagnostics();
Serial.println(diag.magl);
Serial.println(diag.magh);

That should print two 0s if things are good.

I was having some issues accessing magl and magh from the diagnostics register, but it looks like that won’t be necessary. I tested the sensor with a small neodymium magnet and it reads a magnitude of ~4700 and the position is completely constant. It seems like the noisiness I’ve been observing has largely been due to a weak magnetic field from the ceramic ring magnet that comes by default attached to the motor. Thank you for your help in tracking this issue down–I wish I’d tried this simple test sooner.

1 Like

I’m glad to hear you found it!