3-phase brushless DC (BLDC) motor driver

Hello all,

I request the help from the Arduino community for a robotic project. I would like to turn ON everytime a 3-phase brushless motor with the BLDC driver ref MPQ6541-AEC1 and an Arduino ATmega2560.

The MPQ6541-AEC1 is a 3-phase brushless DC (BLDC) motor driver with 3 integrated half-bridges. The 3 half-bridges consist of 6 N-channel power mosfets. The MPQ6541-AEC1 also integrates 6 pre-drivers, 2 gate driver power supplies, and 3 current-sense amplifiers.

Are you able to explain me better how this 3-phase brushless DC (BLDC) motor driver works and improve my code to get something good ?

Pictures :



Datasheet : https://www.monolithicpower.com/en/documentview/productdocument/index/version/2/document_type/Datasheet/lang/en/sku/MPQ6541GQKTE-AEC1/document_id/10554/

Code test_3.ino

#include "pinDefinition.h"
#include "BentiXMotor.h"

#define REMOTE Serial1

BentiXMotor motor1(M1_FAULT_PIN, M1_WAKE_PIN, M1_PWMAL_PIN, M1_PWMBL_PIN, M1_PWMCL_PIN, M1_PWMAH_PIN, M1_PWMBH_PIN, M1_PWMCH_PIN, M1_OUT1_PIN, M1_OUT2_PIN, M1_OUT3_PIN, 255, 0);
BentiXMotor motor2(M2_FAULT_PIN, M2_WAKE_PIN, M2_PWMAL_PIN, M2_PWMBL_PIN, M2_PWMCL_PIN, M2_PWMAH_PIN, M2_PWMBH_PIN, M2_PWMCH_PIN, M2_OUT1_PIN, M2_OUT2_PIN, M2_OUT3_PIN, 255, 0);
BentiXMotor motor3(M3_FAULT_PIN, M3_WAKE_PIN, M3_PWMAL_PIN, M3_PWMBL_PIN, M3_PWMCL_PIN, M3_PWMAH_PIN, M3_PWMBH_PIN, M3_PWMCH_PIN, M3_OUT1_PIN, M3_OUT2_PIN, M3_OUT3_PIN, 255, 0);
BentiXMotor motor4(M4_FAULT_PIN, M4_WAKE_PIN, M4_PWMAL_PIN, M4_PWMBL_PIN, M4_PWMCL_PIN, M4_PWMAH_PIN, M4_PWMBH_PIN, M4_PWMCH_PIN, M4_OUT1_PIN, M4_OUT2_PIN, M4_OUT3_PIN, 255, 0);

long timer;

void setup() {
  Serial.begin(9600);
  Serial.println("Start Drone");

  // Initializing motors
  motor1.initialize();
  motor2.initialize();
  motor3.initialize();
  motor4.initialize();

  // Start Motors
  motor1.setSpeed(255);
  motor2.setSpeed(255);
  motor3.setSpeed(255);
  motor4.setSpeed(255);
  timer = millis();
}

void loop() {
  if (millis() - timer > 10000) {
    motor1.setSpeed(0);
    motor2.setSpeed(0);
    motor3.setSpeed(0);
    motor4.setSpeed(0);
  }

  // currentSense();  // uncomment this line to check current
  checkAndResetFaults();
  checkAndInitializeMotors();
}

void currentSense() {
  int currentSenseA1 = motor1.readCurrentSenseA();
  int currentSenseB1 = motor1.readCurrentSenseB();
  int currentSenseC1 = motor1.readCurrentSenseC();

  int currentSenseA2 = motor2.readCurrentSenseA();
  int currentSenseB2 = motor2.readCurrentSenseB();
  int currentSenseC2 = motor2.readCurrentSenseC();

  int currentSenseA3 = motor3.readCurrentSenseA();
  int currentSenseB3 = motor3.readCurrentSenseB();
  int currentSenseC3 = motor3.readCurrentSenseC();

  int currentSenseA4 = motor4.readCurrentSenseA();
  int currentSenseB4 = motor4.readCurrentSenseB();
  int currentSenseC4 = motor4.readCurrentSenseC();

  Serial.println("Motor 1 Current Sense:");
  Serial.print("Phase A: ");
  Serial.println(currentSenseA1);
  Serial.print("Phase B: ");
  Serial.println(currentSenseB1);
  Serial.print("Phase C: ");
  Serial.println(currentSenseC1);

  Serial.println("Motor 2 Current Sense:");
  Serial.print("Phase A: ");
  Serial.println(currentSenseA2);
  Serial.print("Phase B: ");
  Serial.println(currentSenseB2);
  Serial.print("Phase C: ");
  Serial.println(currentSenseC2);

  Serial.println("Motor 3 Current Sense:");
  Serial.print("Phase A: ");
  Serial.println(currentSenseA3);
  Serial.print("Phase B: ");
  Serial.println(currentSenseB3);
  Serial.print("Phase C: ");
  Serial.println(currentSenseC3);

  Serial.println("Motor 4 Current Sense:");
  Serial.print("Phase A: ");
  Serial.println(currentSenseA4);
  Serial.print("Phase B: ");
  Serial.println(currentSenseB4);
  Serial.print("Phase C: ");
  Serial.println(currentSenseC4);
}

void checkAndResetFaults() {
  if (motor1.checkFault()) {
    Serial.println("Motor 1 fault detected. Resetting...");
    motor1.reset();
  }
  if (motor2.checkFault()) {
    Serial.println("Motor 2 fault detected. Resetting...");
    motor2.reset();
  }
  if (motor3.checkFault()) {
    Serial.println("Motor 3 fault detected. Resetting...");
    motor3.reset();
  }
  if (motor4.checkFault()) {
    Serial.println("Motor 4 fault detected. Resetting...");
    motor4.reset();
  }
}

void checkAndInitializeMotors() {
  if (motor1.checkWake()) {
    Serial.println("Motor 1 woke up. Initializing...");
    motor1.initialize();
  }
  if (motor2.checkWake()) {
    Serial.println("Motor 2 woke up. Initializing...");
    motor2.initialize();
  }
  if (motor3.checkWake()) {
    Serial.println("Motor 3 woke up. Initializing...");
    motor3.initialize();
  }
  if (motor4.checkWake()) {
    Serial.println("Motor 4 woke up. Initializing...");
    motor4.initialize();
  }
}

Code BentiXMotor.cpp

#include "BentiXMotor.h"

BentiXMotor::BentiXMotor(int faultPin, int wakePin, int pwmALPin, int pwmBLPin, int pwmCLPin, int pwmAHPin, int pwmBHPin, int pwmCHPin, int out1Pin, int out2Pin, int out3Pin, int maxSpeed, int minSpeed) {
  M_FAULT = faultPin;
  M_WAKE = wakePin;
  M_PWMAL = pwmALPin;
  M_PWMBL = pwmBLPin;
  M_PWMCL = pwmCLPin;
  M_PWMAH = pwmAHPin;
  M_PWMBH = pwmBHPin;
  M_PWMCH = pwmCHPin;
  M_OUT1 = out1Pin;
  M_OUT2 = out2Pin;
  M_OUT3 = out3Pin;
  MAX_SPEED = maxSpeed;
  MIN_SPEED = minSpeed;

  // Set pin modes
  pinMode(M_FAULT, INPUT_PULLUP);  // Fault pin
  pinMode(M_WAKE, OUTPUT);         // Wake pin
  pinMode(M_PWMAL, OUTPUT);        // Phase A enable pin
  pinMode(M_PWMBL, OUTPUT);        // Phase B enable pin
  pinMode(M_PWMCL, OUTPUT);        // Phase C enable pin
  pinMode(M_PWMAH, OUTPUT);        // Phase A PWM pin
  pinMode(M_PWMBH, OUTPUT);        // Phase B PWM pin
  pinMode(M_PWMCH, OUTPUT);        // Phase C PWM pin
  pinMode(M_OUT1, INPUT);          // Current sense output for Phase A
  pinMode(M_OUT2, INPUT);          // Current sense output for Phase B
  pinMode(M_OUT3, INPUT);          // Current sense output for Phase C

  // Set initial states
  digitalWrite(M_WAKE, HIGH);  // Normal operation
  digitalWrite(M_PWMAL, HIGH); // Enable Phase A
  digitalWrite(M_PWMBL, HIGH); // Enable Phase B
  digitalWrite(M_PWMCL, HIGH); // Enable Phase C
}

void BentiXMotor::setSpeed(int speed) {
  int mappedSpeed = map(speed, 0, 255, MIN_SPEED, MAX_SPEED);
  analogWrite(M_PWMAH, mappedSpeed);
  analogWrite(M_PWMBH, mappedSpeed);
  analogWrite(M_PWMCH, mappedSpeed);
}

void BentiXMotor::stop() {
  setSpeed(MIN_SPEED);
}

void BentiXMotor::start() {
  setSpeed(MAX_SPEED);
}

void BentiXMotor::sleep(bool enableSleep) {
  digitalWrite(M_WAKE, enableSleep ? LOW : HIGH);
}

void BentiXMotor::enablePhaseA(bool enable) {
  digitalWrite(M_PWMAL, enable ? HIGH : LOW);
}

void BentiXMotor::enablePhaseB(bool enable) {
  digitalWrite(M_PWMBL, enable ? HIGH : LOW);
}

void BentiXMotor::enablePhaseC(bool enable) {
  digitalWrite(M_PWMCL, enable ? HIGH : LOW);
}

int BentiXMotor::readCurrentSenseA() {
  return analogRead(M_OUT1);
}

int BentiXMotor::readCurrentSenseB() {
  return analogRead(M_OUT2);
}

int BentiXMotor::readCurrentSenseC() {
  return analogRead(M_OUT3);
}

int BentiXMotor::max_speed() {
  return MAX_SPEED;
}


int BentiXMotor::min_speed(){
  return MIN_SPEED;
}

bool BentiXMotor::checkFault() {
  return !digitalRead(M_FAULT);
}

void BentiXMotor::reset() {
  digitalWrite(M_WAKE, LOW); 
  delay(100);
  digitalWrite(M_WAKE, HIGH);
}

bool BentiXMotor::checkWake() {
  return digitalRead(M_WAKE);
}

void BentiXMotor::initialize() {
  digitalWrite(M_PWMAL, HIGH);
  digitalWrite(M_PWMBL, HIGH);
  digitalWrite(M_PWMCL, HIGH);
  digitalWrite(M_PWMAH, HIGH);
  digitalWrite(M_PWMBH, HIGH);
  digitalWrite(M_PWMCH, HIGH);
  
  analogWrite(M_PWMAL, 128);
  analogWrite(M_PWMBL, 128);
  analogWrite(M_PWMCL, 128);
}

Code BentiXMotor.h

#ifndef BENTIX_MOTOR_H
#define BENTIX_MOTOR_H

#include <Arduino.h>

class BentiXMotor {
private:
  // Pin declarations
  int M_FAULT;
  int M_WAKE;
  int M_PWMAL;
  int M_PWMBL;
  int M_PWMCL;
  int M_PWMAH;
  int M_PWMBH;
  int M_PWMCH;
  int M_OUT1;
  int M_OUT2;
  int M_OUT3;

  // Motor control parameters
  int MAX_SPEED;
  int MIN_SPEED;

public:
  // Constructor
  BentiXMotor(int faultPin, int wakePin, int pwmALPin, int pwmBLPin, int pwmCLPin, int pwmAHPin, int pwmBHPin, int pwmCHPin, int out1Pin, int out2Pin, int out3Pin, int maxSpeed, int minSpeed);

  // Function to set motor speed
  void setSpeed(int speed);

  // Function to stop the motor
  void stop();

  // Function to start the motor at maximum speed
  void start();

  // Function to enter or exit sleep mode
  void sleep(bool enableSleep);

  // Function to enable or disable Phase A
  void enablePhaseA(bool enable);

  // Function to enable or disable Phase B
  void enablePhaseB(bool enable);

  // Function to enable or disable Phase C
  void enablePhaseC(bool enable);

  // Function to read current sense value for Phase A
  int readCurrentSenseA();

  // Function to read current sense value for Phase B
  int readCurrentSenseB();

  // Function to read current sense value for Phase C
  int readCurrentSenseC();

  // Function to get max speed
  int max_speed();

  // Function to get min speed
  int min_speed();

  bool checkFault();
  void reset();
  bool checkWake();
  void initialize();
};

#endif

Code pinDefinition.h

// LEDS
#define LED_1 32 //PC5
#define LED_2 31 //PC6
#define LED_3 30 //PC7

// MOTOR 1
#define M1_FAULT_PIN 49 //PL0
#define M1_WAKE_PIN 48 //PL1
#define M1_PWMAL_PIN 47 //PL2
#define M1_PWMAH_PIN 46 //PL3
#define M1_PWMBL_PIN 43 //PL6
#define M1_PWMBH_PIN 44 //PL5
#define M1_PWMCL_PIN 42 //PL7
#define M1_PWMCH_PIN 45 //PL4
#define M1_OUT1_PIN A3 //PF3
#define M1_OUT2_PIN A4 //PF4
#define M1_OUT3_PIN A5 //PF5

// MOTOR 2
#define M2_FAULT_PIN 33 //PC4
#define M2_WAKE_PIN 34 //PC3
#define M2_PWMAL_PIN 35 //PC2
#define M2_PWMBL_PIN 36 //PC1
#define M2_PWMCL_PIN 37 //PC0
#define M2_PWMAH_PIN 12 //PB6
#define M2_PWMBH_PIN 11 //PB5
#define M2_PWMCH_PIN 10 //PB4
#define M2_OUT1_PIN A0 //PF0
#define M2_OUT2_PIN A1 //PF1
#define M2_OUT3_PIN A2 //PF2

// MOTOR 3
#define M3_FAULT_PIN 53 //PB0
#define M3_WAKE_PIN 39 //PG2
#define M3_PWMAL_PIN 6 //PH3
#define M3_PWMBL_PIN 16 //PH1
#define M3_PWMCL_PIN 17 //PH0
#define M3_PWMAH_PIN 9 //PH6
#define M3_PWMBH_PIN 8 //PH5
#define M3_PWMCH_PIN 7 //PH4
#define M3_OUT1_PIN A8 //PK0
#define M3_OUT2_PIN A7 //PF7
#define M3_OUT3_PIN A6 //PF6


// MOTOR 4
#define M4_FAULT_PIN 15 //PJ0
#define M4_WAKE_PIN 14 //PJ1
#define M4_PWMAL_PIN 26 //PA4
#define M4_PWMBL_PIN 27 //PA5
#define M4_PWMCL_PIN 28 //PA6
#define M4_PWMAH_PIN 5 //PE3
#define M4_PWMBH_PIN 2 //PE4
#define M4_PWMCH_PIN 3 //PE5
#define M4_OUT1_PIN A9 //PK1
#define M4_OUT2_PIN A10 //PK2
#define M4_OUT3_PIN A11 //PK3

Thanks again for your action.