Downsampling Serial

Dear All,

This is a forked thread from: Speed limit on B-G431B-ESC1 with 2212 920kv motor

Now that I have things working quite well, I am testing and fine tuning. I am now becoming ever more aware that with my configuration using the MXLEMMINGObserverSensor, there is a slightly high pitched noise that increases with speed. I have played around with my tuning and nothing seems to make it go away. It is not so bad, but noticeable. Any ideas on how to mitigate this welcome.

/** 
 * B-G431B-ESC1 position motion control example with encoder
 *
 */
#include <SimpleFOC.h>
#include <SimpleFOCDrivers.h>
#include <encoders/MXLEMMING_observer/MXLEMMINGObserverSensor.h>

// Motor instance
//BLDCMotor motor = BLDCMotor(7, 0.14, 2450, 0.00003);
//BLDCMotor motor = BLDCMotor(7, 0.15, 940, 0.000125);
BLDCMotor motor = BLDCMotor(7, 0.14, 850, 0.0000425);
BLDCDriver6PWM driver = BLDCDriver6PWM(A_PHASE_UH, A_PHASE_UL, A_PHASE_VH, A_PHASE_VL, A_PHASE_WH, A_PHASE_WL);
// Gain calculation shown at https://community.simplefoc.com/t/b-g431b-esc1-current-control/521/21
LowsideCurrentSense currentSense = LowsideCurrentSense(0.003f, -64.0f/7.0f, A_OP1_OUT, A_OP2_OUT, A_OP3_OUT);

// encoder instance
MXLEMMINGObserverSensor sensor = MXLEMMINGObserverSensor(motor);

HardwareSerial Serial1(PB6, PB7);

// velocity set point variable
float target = 0;
float targetP = 0;
float targetI = 0;
float targetV = 0;
// instantiate the commander
Commander commandComp = Commander(Serial);
Commander commandESP = Commander(Serial1);
void doTargetP(char* cmd) { commandComp.scalar(&targetP, cmd); }
void doTargetI(char* cmd) { commandComp.scalar(&targetI, cmd); }
void doTargetV(char* cmd) { commandESP.scalar(&targetV, cmd); }

void setup() {

  //pinMode(LED_RED, OUTPUT); // Set board LED for debugging
  //digitalWrite(LED_RED, HIGH);
  
  // use monitoring with serial 
  Serial.begin(115200);
  Serial1.begin(115200);

  // enable more verbose output for debugging
  // comment out if not needed
  SimpleFOCDebug::enable(&Serial);

  // initialize encoder sensor hardware
  sensor.init();

  // link the motor to the sensor
  motor.linkSensor(&sensor);
  
  // driver config
  // power supply voltage [V]
  driver.voltage_power_supply = 12;
  driver.init();
  // link the motor and the driver
  motor.linkDriver(&driver);
  // link current sense and the driver
  currentSense.linkDriver(&driver);

  // initialise the current sensing
  if(!currentSense.init()){
    Serial.println("Current sense init failed.");
    return;
  }
  // no need for aligning
  currentSense.skip_align = true;
  motor.linkCurrentSense(&currentSense);

  motor.sensor_direction= Direction::CW;
  motor.zero_electric_angle = 0;

  // set motion control loop to be used
  motor.controller = MotionControlType::velocity;
  motor.torque_controller = TorqueControlType::foc_current;
  //motor.torque_controller = TorqueControlType::dc_current;
  //motor.foc_modulation = FOCModulationType::SpaceVectorPWM;

  motor.current_sp = motor.current_limit;

  // velocity PI controller parameters
  motor.PID_velocity.P = 0.01;
  motor.PID_velocity.I = 0.004;

  driver.voltage_limit = 10;
  motor.voltage_limit = 5;
  //motor.current_limit = 0.5;

  motor.PID_velocity.limit = motor.voltage_limit;

  // jerk control using voltage voltage ramp
  // default value is 300 volts per sec  ~ 0.3V per millisecond
  motor.PID_velocity.output_ramp = 10;
 
  // velocity low pass filtering time constant
  //motor.LPF_velocity.Tf = 0.1;

  // comment out if not needed
  motor.useMonitoring(Serial);

  motor.monitor_downsample = 10000;
  //motor.motion_downsample = 4;
  
  // initialize motor
  motor.init();
  // align encoder and start FOC
  motor.initFOC();

  // add target command T
  commandComp.add('P', doTargetP, "target P");
  commandComp.add('I', doTargetI, "target I");
  commandESP.add('V', doTargetV, "target V");

  Serial.println(F("Motor ready."));
  Serial.println(F("Set the target velocity using serial terminal:"));
  _delay(1000);
}

void loop() {
  // main FOC algorithm function
  motor.loopFOC();

  //motor.PID_velocity.P = targetP;
  //motor.PID_velocity.I = targetI;

  //Serial.println(target);

  // Motion control function
  motor.move(targetV);

  if (abs(motor.target) < 20.0f && motor.enabled==1)
    motor.disable();
  if (abs(motor.target) >= 20.0f && motor.enabled==0)
    motor.enable();

  // function intended to be used with serial plotter to monitor motor variables
  // significantly slowing the execution down!!!!
  //motor.monitor();
  
  // user communication
  commandESP.run();
  commandComp.run();

}

I am realizing that it seems to be the commander serial runs that are slowing things down. I can downsample the motor.motion_downsample, but would it be better to downsample the reading of the serial. Is there a method for that?

Wouldn’t it just be a matter of not calling your commander run functions every frame? Try only calling them once every few seconds to see how it sounds without any disturbance at all. It may be the noise is coming from the velocity PID. When I was trying to make my CNC spindle quieter, what ended up working best was to command a slightly higher speed than it can reach at its voltage limit, so the PID output stops changing once it gets up to speed. That approach probably won’t work in your case since you need precisely controlled speed, but it may be a clue for how to approach it.

Try adding a lowpass filter on the velocity PID output, so it’s not able to inject high frequency noise into the sine waves. Maybe downsample it too, if you can get loopFOC to the full 25KHz PWM frequency without the PID update being too slow. Lowpass should help smooth it so there’s no large change each time it runs (ears are ridiculously sensitive to any kind of discontinuity)

Thanks @dekutree,

I hope you saw the video of the sirens that I posted in the other thread. It definitely is the commander calls. The sound basically goes away with no commander calls. I tried exactly what you said yesterday and it does help, but it looked a bit messy. What really helped and made the sound basically go away was: motor.motion_downsample = 1;

I also added motor.LPF_velocity.Tf = 0.01; It seems to help a bit but is negligible in comparison to just downsampling the motion by 1. Is that the LPF you are talking about? If not, how would you apply it?

I am pretty happy with this how this sounds now and need to pack the sirens today as I leave on Saturday for the concerts in the US. But once I am in the US, I could tweak some more. See below the current state of the code, as you can see I did try calling the commander every once in a while, but to my ear, the downsample of motion be 1 was fine!

/** 
 * B-G431B-ESC1 position motion control example with encoder
 *
 */
#include <SimpleFOC.h>
#include <SimpleFOCDrivers.h>
#include <encoders/MXLEMMING_observer/MXLEMMINGObserverSensor.h>

// Motor instance
//BLDCMotor motor = BLDCMotor(7, 0.14, 2450, 0.00003);
//BLDCMotor motor = BLDCMotor(7, 0.15, 940, 0.000125);
BLDCMotor motor = BLDCMotor(7, 0.14, 850, 0.0000425);
BLDCDriver6PWM driver = BLDCDriver6PWM(A_PHASE_UH, A_PHASE_UL, A_PHASE_VH, A_PHASE_VL, A_PHASE_WH, A_PHASE_WL);
// Gain calculation shown at https://community.simplefoc.com/t/b-g431b-esc1-current-control/521/21
LowsideCurrentSense currentSense = LowsideCurrentSense(0.003f, -64.0f/7.0f, A_OP1_OUT, A_OP2_OUT, A_OP3_OUT);

// encoder instance
MXLEMMINGObserverSensor sensor = MXLEMMINGObserverSensor(motor);

HardwareSerial Serial1(PB6, PB7);

// velocity set point variable
float target = 0;
float targetP = 0;
float targetI = 0;
float targetV = 0;
// instantiate the commander
Commander commandComp = Commander(Serial);
Commander commandESP = Commander(Serial1);
void doTargetP(char* cmd) { commandComp.scalar(&targetP, cmd); }
void doTargetI(char* cmd) { commandComp.scalar(&targetI, cmd); }
void doTargetV(char* cmd) { commandESP.scalar(&targetV, cmd); }

void setup() {

  //pinMode(LED_RED, OUTPUT); // Set board LED for debugging
  //digitalWrite(LED_RED, HIGH);
  
  // use monitoring with serial 
  Serial.begin(115200);
  Serial1.begin(115200);

  // enable more verbose output for debugging
  // comment out if not needed
  //SimpleFOCDebug::enable(&Serial);

  // initialize encoder sensor hardware
  sensor.init();

  // link the motor to the sensor
  motor.linkSensor(&sensor);
  
  // driver config
  // power supply voltage [V]
  driver.voltage_power_supply = 12;
  driver.init();
  // link the motor and the driver
  motor.linkDriver(&driver);
  // link current sense and the driver
  currentSense.linkDriver(&driver);

  // initialise the current sensing
  if(!currentSense.init()){
    Serial.println("Current sense init failed.");
    return;
  }
  // no need for aligning
  currentSense.skip_align = true;
  motor.linkCurrentSense(&currentSense);

  motor.sensor_direction= Direction::CW;
  motor.zero_electric_angle = 0;

  // set motion control loop to be used
  motor.controller = MotionControlType::velocity;
  motor.torque_controller = TorqueControlType::foc_current;
  //motor.torque_controller = TorqueControlType::dc_current;
  //motor.foc_modulation = FOCModulationType::SpaceVectorPWM;

  motor.current_sp = motor.current_limit;

  // velocity PI controller parameters
  motor.PID_velocity.P = 0.01;
  motor.PID_velocity.I = 0.004;

  driver.voltage_limit = 10;
  motor.voltage_limit = 5;
  //motor.current_limit = 0.2;

  motor.PID_velocity.limit = motor.voltage_limit;

  // jerk control using voltage voltage ramp
  // default value is 300 volts per sec  ~ 0.3V per millisecond
  motor.PID_velocity.output_ramp = 10;
 
  // velocity low pass filtering time constant
  motor.LPF_velocity.Tf = 0.01;

  // comment out if not needed
  //motor.useMonitoring(Serial);

  //motor.monitor_downsample = 100000;
  motor.motion_downsample = 1;
  
  // initialize motor
  motor.init();
  // align encoder and start FOC
  motor.initFOC();

  // add target command T
  commandComp.add('P', doTargetP, "target P");
  commandComp.add('I', doTargetI, "target I");
  commandESP.add('V', doTargetV, "target V");

  Serial.println(F("Motor ready."));
  Serial.println(F("Set the target velocity using serial terminal:"));
  _delay(1000);
}

void loop() {

  // main FOC algorithm function
  motor.loopFOC();

  //motor.PID_velocity.P = targetP;
  //motor.PID_velocity.I = targetI;

  //Serial.println(target);

  // Motion control function
  motor.move(targetV);

  
  if (abs(motor.target) < 20.0f && motor.enabled==1)
    motor.disable();
  if (abs(motor.target) >= 20.0f && motor.enabled==0)
    motor.enable();

  // function intended to be used with serial plotter to monitor motor variables
  // significantly slowing the execution down!!!!
  //motor.monitor();
  
  // user communication
  /*
  static uint32_t lastSerialRead = 0;
  if (lastSerialRead == 32) {
    lastSerialRead = 0;
    commandESP.run();
    commandComp.run();
  }
  lastSerialRead += 1;
  */
  commandESP.run();
  //commandComp.run();
}

Ok, nevermind the lowpass stuff, that was for the hypothetical case of the noise coming from velocity PID.

I’m not sure if UART will ever be fast enough to not cause a small disturbance. One option is to use the servo PWM protocol to control the speed, where the ESP32 would switch a pin on, wait 1000 to 2000 microseconds, and switch it back off. My ESC-side code looks like this:

#define SERVO_PULSE_PIN PA15
volatile uint16_t servoPulse = 1000;
void ServoPulseUpdate() {
  static uint32_t startTime = 0;
  uint32_t curTime = micros();
  if (digitalRead(SERVO_PULSE_PIN)) // Pin transitioned from low to high
    startTime = curTime; // Start counting pulse time
  else // Pin transitioned from high to low
    servoPulse = (uint16_t)(curTime - startTime);
}
void ServoPulseInit{
  pinMode(SERVO_PULSE_PIN, INPUT);
  attachInterrupt(digitalPinToInterrupt(SERVO_PULSE_PIN), ServoPulseUpdate, CHANGE);
}

I often use servo testers as speed knobs, and their output is a bit noisy, but hopefully the ESP32 will give a more stable value. You could also use a longer pulse duration to get more resolution.

Thanks. I am committed to UART on this go around since the boards are so hard to solder and are now in place with UART for communication to the ESP (which is then also controlled by OSC ; )

I was hesitant to use pwm because I would not be able to know exactly the frequency without having some other protocol to talk back to the ESP. With UART, I can specify a frequency to any reasonable precision and the FLux Observer is amazingly accurate. I can notice tuning accuracy down to hundreths of a Hz!

No reason you can’t communicate PWM using one of the UART pins. Just don’t call serial.begin. It is true you won’t have quite as fine of control, but you can increase the resolution almost arbitrarily high. Change to using CPU timers instead of micros() for an instant 180x increase (ESC is 180MHz, ESP32 is even higher). And instead of 1000-2000us, maybe 10us-20000us. That’s another ~20x higher resolution, and still about 50Hz update rate. And maybe have the ESP32 send sqrt(target) and ESC square the received value, so you have the same number of steps per octave at any frequency in the integer PWM period format.

Or you could use the two UART lines to communicate digital data with an I2C type protocol.

Thanks! I will look into it after I get back from the US. Things are stable now and time has run out for more fiddling. Here is a nice video than the first that I made today. Again, I am so grateful for all the help!