High Pitch Whine from Motor

Hi Folks,

I’m using the DRV8302 board to drive an AC servo motor in closed loop mode with current control. I’m using a Nucleo64 F401RE with SimpleFOC 2.2.2. I’ve used this combination in the past, but I’m now working from PlatformIO for development. When the motor is in use, it emits a whine whose volume is dependent on load/Iq current. In the past when building from the Arduino IDE, I’ve used this exact combination before, with no audible whine from the motor. I measured the frequency, and it’s almost exactly1 khz.

I’ve tried changing the PWM frequency, but that doesn’t have any effect. I also measured the loop time, and measured ~300 uS per loop.

Curious if anyone else has heard this noise before. Other than the noise, the motor and controller perform flawlessly.

I had the same problem, following the debugger found it was using generic pwm code and not stm32 specific, which wasn’t effective.

@runger pointed me to the solution:

If you are using PIO if lib_archive = false is not set in platformio.ino it will not use stm32 specific includes.

Ciao!

Hey @deffie, thanks for the note. I did not have lib_archive = false in my platform.ini file. When I added it however, the SimpleFOC startup procedure doesn’t work anymore, the motor and controller do not initialize (but compilation succeeds).

@runger Any ideas here? If helpful I can paste my code.

Code would help! And the ini too. Oh and do a clean build before.

Thanks! I did a clean build, but that didn’t work.

Below is the .ini file:

; PlatformIO Project Configuration File
;
;   Build options: build flags, source filter
;   Upload options: custom upload port, speed and extra flags
;   Library options: dependencies, extra library storages
;   Advanced options: extra scripting
;
; Please visit documentation for the other options and examples
; https://docs.platformio.org/page/projectconf.html

[env:nucleo_f401re]
platform = ststm32
board = nucleo_f401re
framework = arduino
monitor_speed = 115200
lib_archive = false
lib_deps =
  # RECOMMENDED
  # Accept new functionality in a backwards compatible manner and patches
  https://github.com/simplefoc/Arduino-FOC.git#v2.2.2

And my code:

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

// DRV8302 pins connections
//#define INH_A PA8
//#define INH_B PA9
//#define INH_C PA10
#define INH_A PB13
#define INH_B PB14
#define INH_C PB15

#define EN_GATE PB7
#define M_PWM PB4
#define M_OC PB3
#define OC_ADJ PB6
#define OC_GAIN PB5

#define IOUTA A0
#define IOUTB A1
#define IOUTC A2

// Motor instance
BLDCMotor motor = BLDCMotor(4);
BLDCDriver3PWM driver = BLDCDriver3PWM(INH_A, INH_B, INH_C, EN_GATE);

// DRV8302 board has 0.005Ohm shunt resistors and the gain of 12.22 V/V
LowsideCurrentSense cs = LowsideCurrentSense(0.005f, 12.22f, IOUTA, IOUTB, IOUTC);

// encoder instance
Encoder encoder = Encoder(PB8, PB9, 2048);

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

// commander interface
Commander command = Commander(Serial);
void onMotor(char* cmd){ command.motor(&motor, cmd); }


void setup() {

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

  // DRV8302 specific code
  // M_OC  - enable overcurrent protection
  pinMode(M_OC,OUTPUT);
  digitalWrite(M_OC,LOW);
  // M_PWM  - enable 3pwm mode
  pinMode(M_PWM,OUTPUT);
  digitalWrite(M_PWM,HIGH);
  // OD_ADJ - set the maximum overcurrent limit possible
  // Better option would be to use voltage divisor to set exact value
  pinMode(OC_ADJ,OUTPUT);
  digitalWrite(OC_ADJ,HIGH);
  pinMode(OC_GAIN,OUTPUT);
  digitalWrite(OC_GAIN,LOW);

  // driver config
  // power supply voltage [V]
  driver.voltage_power_supply = 24;
  driver.pwm_frequency = 18000; // suggested under 18khz
  driver.init();
  // link the motor and the driver
  motor.linkDriver(&driver);
  // link current sense and the driver
  cs.linkDriver(&driver);

  // align voltage
  motor.voltage_sensor_align = 2.0;

  // control loop type and torque mode 
  motor.torque_controller = TorqueControlType::foc_current;
  motor.controller = MotionControlType::velocity;
  motor.motion_downsample = 0.0;

  // velocity loop PID
  motor.PID_velocity.P = 0.2;
  motor.PID_velocity.I = 5.0;
  // Low pass filtering time constant 
  motor.LPF_velocity.Tf = 0.02;
  // angle loop PID
  motor.P_angle.P = 20.0;
  // Low pass filtering time constant 
  motor.LPF_angle.Tf = 0.0;

  // current q loop PID 
  motor.PID_current_q.P = 3.0;
  motor.PID_current_q.I = 100.0;
  // Low pass filtering time constant 
  motor.LPF_current_q.Tf = 0.02;
  // current d loop PID
  motor.PID_current_d.P = 3.0;
  motor.PID_current_d.I = 100.0;
  // Low pass filtering time constant 
  motor.LPF_current_d.Tf = 0.02;

  // Limits 
  motor.velocity_limit = 100.0; // 100 rad/s velocity limit
  motor.voltage_limit = 12;   // 12 Volt limit 
  motor.current_limit = 1.0;    // 2 Amp current limit

  // use monitoring with serial for motor init
  // monitoring port
  Serial.begin(115200);
  // comment out if not needed
  motor.useMonitoring(Serial);
  motor.monitor_variables = _MON_CURR_Q | _MON_CURR_D; // monitor the two currents d and q
  motor.monitor_downsample = 0;

  // initialise motor
  motor.init();

  cs.init();
  // driver 8302 has inverted gains on all channels
  cs.gain_a *=-1;
  cs.gain_b *=-1;
  cs.gain_c *=-1;
  motor.linkCurrentSense(&cs);

  // align encoder and start FOC
  motor.initFOC();

  // set the inital target value
  motor.target = 0;

  // define the motor id
  command.add('M', onMotor, "motor");

  Serial.println(F("Full control example: "));
  Serial.println(F("Run user commands to configure and the motor (find the full command list in docs.simplefoc.com) \n "));
  Serial.println(F("Initial motion control loop is voltage loop."));
  Serial.println(F("Initial target voltage 2V."));

  _delay(1000);


}

void loop() {

  // iterative setting FOC phase voltage
  motor.loopFOC();

  // iterative function setting the outter loop target
  motor.move();

  // monitoring the state variables
  motor.monitor();

  // user communication
  command.run(); 

}

The only thing I can maybe think of is that I am using slightly different PWM pins for INH_A, INH_B, and INH_C. I am connecting them to PWM/1N, PWM1/2N, and PWM1/3N on the Nucleo. I’m not sure what the “N” means on the PWM description…

Thank you!!

Check here for pwm pins explanation

Looks like they are interdependent, better/easier if you pick independent pwm channels eg. different first numbers

And I would use STM pin/port naming for analog channels too

The rest of the code looks ok to me

Error from the init could be useful as well

So when I have “lib_archive = false”, compilation appears to succeed (it says so in the terminal), but no serial outputs come through as you would expect with the code having monitoring enabled, e.g., no motor init, no pole pair checks, no current sense checks, etc. It just sits there not initializing.

I’m not too familiar with the capabilities of PlatformIO, so if there’s other information I can get that would be helpful, I’d appreciate any pointers!

@deffie I thought the recommendation was to use the same PWM timer for the 3 PWM signals?

Update - I tried changing the PWM pins to PA8, PA9, and PA10 - this worked and now the whine is gone. Thank you all for the help!

1 Like