Motor has a high pitched noise when using a SAMD51 processor (Adafruit Metro M4 Express)

The Background:
I have a 48V power supply that can push a current of 32A. I’m trying to drive a large BLDC motor rated at 48V 61A (FL80BLS120), I am using the DRV8301 driver to drive the motor and am controlling the driver with the Adafruit Metro M4 Express Dev board (SAMD51J19A). There are hall sensor encoders attached to the motor so I can determine the velocity and angle of the motor shaft.

Previously I was using an Arduino Uno to move the motor and was using software interrupts to read the 3 hall sensor values. Everything was working fine on the Arduino (no noise from the motor and relatively smooth movement), I was doing this just for ease and sanity but I’m at the point where I need to switch to a SAMD processor and use hardware interrupts to read the hall sensors which is why I’m switching to the Adafruit Metro M4 Express (along with other reasons I wont get into).

The Problem:
The Adafruit Metro M4 Express runs at 120Mhz while the Arduino Uno runs at 16Mhz. Since the clock frequency is much higher, its telling the motor to move at a higher clock speed causing the high pitched sound coming from the motor.

Things I troubleshooted:

  • Power supply: I receive the same issue even if I used a 12v or 24v power supply
  • MCU: I don’t receive this issue on an Arduino Uno regardless of the power supply used
  • Driver: I receive this issue on both the DRV8302 and DRV8301 (though the sound when using the DRV8301 with SPI communication is a bit better)
  • Motion Control Types: This sound occurs in both open and closed loop and am using velocity closed loop mode to do my tests at the moment (since I’m working on also tuning PID values)

Research i’ve done:
I scoured the forums to see if I could find any solutions and found that there should be support for the Adafruit Metro M4 express. I found in “drivers/hardware_specific/samd” code to possibly help me configure the pins and timers properly so that they are outputting at a correct pwm clock cycle (like 20khz).

When I print “printAllPinInfos()” from the samd_mcu.cpp file I get:
Pin 00 PA23 E= None F=TCC1-3[7] G=TCC 0-3[3]
Pin 01 PA22 E= None F=TCC1-2[6] G=TCC 0-2[2]
Pin 02 PB17 E= None F= None G=TCC 0-5[5]
Pin 03 PB16 E= None F= None G=TCC 0-4[4]
Pin 04 PB13 E= None F= None G=TCC 0-1[1]
Pin 05 PB14 E= None F= None G=TCC 0-2[2]
Pin 06 PB15 E= None F= None G=TCC 0-3[3]
Pin 07 PB12 E= None F= None G=TCC 0-0[0]
Pin 08 PA21 E= None F=TCC1-1[5] G=TCC 0-1[1]
Pin 09 PA20 E= None F=TCC1-0[4] G=TCC 0-0[0]
Pin 10 PA18 E= TC3-0[0] F=TCC1-2[2] G=TCC 0-0[6]
Pin 11 PA19 E= TC3-1[1] F=TCC1-3[3] G=TCC 0-1[7]
Pin 12 PA17 E= TC2-1[1] F=TCC1-1[1] G=TCC 0-5[5]
Pin 13 PA16 E= TC2-0[0] F=TCC1-0[0] G=TCC 0-4[4]
Pin 14 PA02 E= None F= None G= None
Pin 15 PA05 E= TC0-1[1] F= None G= None
Pin 16 PA06 E= TC1-0[0] F= None G= None
Pin 17 PA04 E= TC0-0[0] F= None G= None
Pin 18 PB08 E= None F= None G= None
Pin 19 PB09 E= None F= None G= None
Pin 20 PB02 E= None F=TCC2-2[2] G= None
Pin 21 PB03 E= None F= None G= None
Pin 22 PB02 E= None F=TCC2-2[2] G= None
Pin 23 PB03 E= None F= None G= None
Pin 24 PA14 E= TC3-0[0] F=TCC2-0[0] G=TCC 1-2[2]
Pin 25 PA13 E= TC2-1[1] F=TCC0-1[7] G=TCC 1-3[3]

When I try to configure the PWM frequency of my pins using “_configure3PWM(24000, 11, 12, 13);” I get an error “SAMD: Bad pin combination!”. I read that we want all the pins to be on the same clock (clock 4 if I’m not mistaken) so I tried “_configure3PWM(24000, 4, 12, 13);” since each of those pins can be used with clock 4 but it didn’t help.

My Code:

#include <Arduino.h>
#define _SAMD51_
#define SIMPLEFOC_SAMD_DEBUG 
#include <SimpleFOC.h>
#include <DRV8301.h>

#define   INH_A 11
#define   INH_B 12
#define   INH_C 13
#define   EN_GATE 8
#define nFAULT A2
#define nOCTW A3
#define MOTOR1_CS_PIN 	7

float target = 0.0; // [rad/s]

HallSensor sensor = HallSensor(2, 3, 4, 8); //Hall sensor instance (hallA, hallB, hallC, pole pairs)
BLDCMotor motor = BLDCMotor(8); // Motor instance (pole pairs)
BLDCDriver3PWM driver = BLDCDriver3PWM(INH_A, INH_B, INH_C);
DRV8301 gate_driver = DRV8301(26, 24, 25, MOTOR1_CS_PIN, EN_GATE, A2); //SPI COMMUNICATION DRV8301 gate_driver = DRV8301(MOSI, MISO, SCLK, CS, EN_GATE, FAULT);

// Interrupt routine intialization for hall sensors
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
void doC(){sensor.handleC();}

void setupHallSensor(){
    sensor.init(); // initialize encoder hardware
    sensor.enableInterrupts(doA, doB, doC); // hardware interrupt enable

    motor.linkSensor(&sensor); // link the motor to the sensor
}

void serialReceiveUserCommand()
{
    // a string to hold incoming data
    static String received_chars;

    while (Serial.available())
    {
        char inChar = (char)Serial.read(); // get the new byte:
        received_chars += inChar; // add it to the string buffer:
        if (inChar == '\n') // end of user input
        {
            target = received_chars.toFloat(); // change the motor target
            Serial.print("Target = ");
            Serial.println(target);
            received_chars = ""; // reset the command buffer
        }
    }
}

void setup()
{
    Serial.begin(115200);
    setupHallSensor();

    // driver config
    driver.voltage_power_supply = 48; // power supply voltage [V]
    driver.voltage_limit = 48;
    driver.pwm_frequency = 120000000; // default 20kHz
    driver.init();

    gate_driver.begin(PWM_INPUT_MODE_3PWM);
    motor.linkDriver(&driver); // link the motor and the driver

    //Limiting motor movements
    motor.voltage_limit = 48;       // [V]
    motor.velocity_limit = 15;      // [rad/s]
    motor.current_limit = 30;       // [A]
    motor.phase_resistance = 0.156; // [Ohm]
	motor.voltage_sensor_align = 5; // [V]

	//Closed loop velocity properties
	motor.PID_velocity.P = 0.6;
	motor.PID_velocity.I = 6.0;
        motor.PID_velocity.D = 0.04;

	motor.LPF_velocity.Tf = 0.15; //Low pass filter [seconds] (0.01 = 10 milliseconds)

        motor.motion_downsample = 50; // divider for the motion control loop, used to reduce the load on the mcu

    motor.controller = MotionControlType::velocity; // closed loop velocity

    motor.useMonitoring(Serial);
    SimpleFOCDebug::enable();
    
    motor.init(); // init motor hardware
    motor.initFOC(3.14, Direction::CW); // init foc algorithm (foc_angle, direction)

    printAllPinInfos();
    _configure3PWM(20000, INH_A, INH_B, INH_C); // configure 3PWM outputs

    _delay(1000);
}

void loop()
{
	serialReceiveUserCommand(); // receive the used commands from serial

	motor.loopFOC();

    if(nFAULT == 1 || nOCTW == 1){
        motor.disable(); // disable motor if driver reports faults
        Serial.println("DRV8301 error");
    } 
    else motor.move(target); // set the motor movement to the target velocity

	motor.monitor();
}

Would someone be able to help me understand how to properly configure the pins on the Adafruit Metro M4 Express so that I can run the motor without this high pitched noise/while from the motor.

I don’t believe that’s how it works. Could you please read the documentation more carefully?

120,000,000 is 120MHz.

Are you sure about this?

Valentine

1 Like

The audible hearing range is 20Hz- 20kHz, you will never hear anything at these frequencies (no matter 16MHz or 160MHz).

The clock frequency != PWM frequency. You can have higher PWM frequency with a higher MCU base freq, but you still need many internal clock cycles to calculate the PWM cycle. You can’t have a PWM frequency that matches the frequency of the controller because you would have no time to calculate what the output should be. Also, the transistors in the DRV8301, 8302 probably can not switch this fast. From the datasheet recommended operating conditions: Switching frequency 200kHz

Can you try motor.initFOC without the parameters? Your parameters may not/ are probably not right (numbers are too clean).

You should also try to remove the downsampling, it’s possible that your config is failing during setting PWM speed, so it defaults PWM to 20kHz, then you are downsampling 50x and well into the audible region.

1 Like

My reasoning for setting the driver to the frequency of 120000000 was because I was thinking it needed to match the clock freq of the processor controlling the driver. I see I was mistaken, still trying to figure out how to properly use the simplefoc library as well as the parameters I need to set.

Changing
driver.pwm_frequency = 20000
still causes the high pitch noise to come from the motor though

To your first point of trying motor.initFOC without parameters:
I got the parameters by using:

motor.useMonitoring(Serial);
Serial.println(motor.zero_electric_angle);
Serial.println(sensor.direction);
motor.disable();
while(true);

The electric angle returned as 3.14 and the sensor.direction returned 1 which is why I set motor.initFOC(3.14, Direction::CW)

MOT: Align sensor.
MOT: sensor_direction==CW
MOT: PP check: OK!
MOT: Zero elec. angle: 3.14
MOT: No current sense.
MOT: Ready.
3.14
1

As you asked I tried to remove the parameters from initFOC but it only caused the high pitch noise to be even louder. I tried playing with the values a bit but the best results I found were with 3.14 and CW direction.

Second point about PWM speed config failing causing the default to be set:
How do I go about debugging this?

Third point about removing downsampling:
I added this originally to smooth out the motor movement when using the Arduino. But was originally set to 5. I increased it to 50 because i was thinking that since the Adafruit Metro M4 Express operated at 120Mhz I would need to increase the downsampling.

Anyways, I commented it out for now but it didn’t change anything when it comes to the high pitch noise coming from the motor unfortunately.

Note:
The motor only produces an audible noise when moving. When idle, the motor seems to be quite. I say seems to be because it could just be very low and the noise of the power supply is overpowering the subtle high pitch noise form the motor while in idle

Is it possible to use an app like PhyPhox to determine the frequency? It might help to find the source.

Is the sound worse at higher speeds? I am wondering if it is related to the commutation pattern, but this is likely not it because it was silent on Uno where the interrupt will take up more real-world time. The fact that you only hear the noise when moving indicates it is related to commutation but is probably not related to the interrupt load.

If you set the power supply voltage parameter to your full voltage, but change motor.voltage_limit to something smaller, like 1/2 supply voltage, or even 1/4, do you still get the noise?

Hey @moshea-kdtech-dev , did you get it working?

The SAMD51 chip on the MetroM4 Express should be supported. It’s a nice MCU for working with SimpleFOC.

The PWM frequency should perhaps be a bit higher (but not 120MHz :smiley: ) . Something like 32kHz should be outside of the audible range:
driver.pwm_frequency = 32000;

If you’re using PlatformIO, please make sure you have a:

lib_archive = false

in your platformio.ini file…

For setting the zero angle, please use a little more accuracy:
Serial.println(motor.zero_electric_angle,5); // 5 decimal places should be as much as float can manage