stm32+SimpleFOC-PowerShield driver lost control problem?

I use stm32f407vgt + powerShield make pcb can driver two motor, bldc motor use Hoverboard motor, hall close loop, but encountered a strange problem , I set two motor speed same as postitve and negative ,motor works noramlly, but set motor one is postitive and one is negative, motor work lost control , print log speed motor1.shaftVelocity() and motor2.shaftVelocity() abnormal, the core config code show as below:

BLDCMotor  motor1 = BLDCMotor(MOTOR_POLES);
BLDCDriver3PWM driver1 = BLDCDriver3PWM(Motor1_U, Motor1_V, Motor1_W, Motor1_U_CS, Motor1_V_CS, Motor1_W_CS);
HallSensor sensor1 = HallSensor(Hall1_U, Hall1_V, Hall1_W, MOTOR_POLES);


BLDCMotor motor2 = BLDCMotor(MOTOR_POLES);
BLDCDriver3PWM driver2 = BLDCDriver3PWM(Motor2_U, Motor2_V, Motor2_W, Motor2_U_CS, Motor2_V_CS, Motor2_W_CS);
HallSensor sensor2 = HallSensor(Hall2_U, Hall2_V, Hall2_W, MOTOR_POLES);  


void doA1(){sensor1.handleA();}
void doB1(){sensor1.handleB();}
void doC1(){sensor1.handleC();}

void doA2(){sensor2.handleA();}
void doB2(){sensor2.handleB();}
void doC2(){sensor2.handleC();}


steup()
{
sensor1.init();
  sensor1.enableInterrupts(doA1, doB1, doC1); 
  sensor2.init();
  sensor2.enableInterrupts(doA2, doB2, doC2); 

  // link the motor to the sensor
  motor1.linkSensor(&sensor1);  
  motor2.linkSensor(&sensor2);  

  // driver config
  // power supply voltage [V]
  motor1.voltage_limit = 10;         
  driver1.voltage_power_supply = 12; 
  driver1.init();
  motor1.linkDriver(&driver1);
  motor1.voltage_sensor_align = 1;   
  motor1.controller = MotionControlType::velocity; 

  motor2.voltage_limit = 10;          
  driver2.voltage_power_supply = 12;  
  driver2.init();
  motor2.linkDriver(&driver2);
  motor2.voltage_sensor_align = 1;  
  motor2.controller = MotionControlType::velocity; 

  // contoller configuration 
  // default parameters in defaults.h

  // velocity PI controller parameters
  
  motor1.PID_velocity.P = 0.6; 
  motor1.PID_velocity.I = 2.0; 
  motor1.PID_velocity.D = 0.001; 
  motor1.LPF_velocity.Tf = 0.04; 
  motor1.PID_velocity.output_ramp = 1000; 

  motor2.PID_velocity.P = 0.6;  
  motor2.PID_velocity.I = 2.0;  
  motor2.PID_velocity.D = 0.001; 
  motor2.LPF_velocity.Tf = 0.04;  
  motor2.PID_velocity.output_ramp = 1000;  

  // initialize motor
  motor1.init();
  motor1.initFOC(4.19, Direction::CW); //motor.initFOC(0.0000, Direction::CCW) 
  motor2.init();
  motor2.initFOC(4.19 Direction::CW); //motor.initFOC(0.0000, Direction::CCW)
}
loop{
      motor1.loopFOC();
      motor1.move(required_motor1_vel);
      motor2.loopFOC();
      motor2.move(required_motor2_vel);
}

1

Hello:

You may help better if you post the complete executable arduino code as well as schematics. The information you provide is insufficient to debug the problem.

Cheers,
Valentine

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

HardwareSerial Serial1(PA10, PA9);
BLDCMotor motor1 = BLDCMotor(15); 
BLDCMotor motor2 = BLDCMotor(15); 
BLDCDriver3PWM driver1 = BLDCDriver3PWM(PB8,  PB6,  PB7, PE6,  PE4, PE5); 
BLDCDriver3PWM driver2 = BLDCDriver3PWM(PE13, PE9, PE11, PE12, PE8, PE10); 
HallSensor sensor1 = HallSensor(PA5, PA6, PD10,  15);
HallSensor sensor2 = HallSensor(PE7, PE14, PE15, 15);
// Interrupt routine intialisation
// channel A and B callbacks
void doA1(){sensor1.handleA();}
void doB1(){sensor1.handleB();}
void doC1(){sensor1.handleC();}
void doA2(){sensor2.handleA();}
void doB2(){sensor2.handleB();}
void doC2(){sensor2.handleC();}

// velocity set point variable

float target_velocity = 0;
float get_velocity = 0;
long timer = 0;

// instantiate the commander
//Commander command = Commander(Serial1);
//void doTarget(char* cmd) { command.scalar(&motor2.target, cmd); }

void setup() {

  Serial1.begin(115200);
  motor1.monitor_variables = _MON_TARGET | _MON_VEL | _MON_ANGLE; 
  motor2.monitor_variables = _MON_TARGET | _MON_VEL | _MON_ANGLE; 
//
  // initialize sensor sensor hardware

  sensor1.init();
  sensor1.enableInterrupts(doA1, doB1, doC1); 
  sensor2.init();
  sensor2.enableInterrupts(doA2, doB2, doC2); 

 

  // link the motor to the sensor
  motor1.linkSensor(&sensor1);  
  motor2.linkSensor(&sensor2);  

  // driver config
  // power supply voltage [V]
  motor1.voltage_limit = 10;         
  driver1.voltage_power_supply = 12; 
  driver1.init();
  motor1.linkDriver(&driver1);
  motor1.voltage_sensor_align = 1;   
  motor1.controller = MotionControlType::velocity; 
  //motor1.controller = MotionControlType::torque; 

  motor2.voltage_limit = 10;          
  driver2.voltage_power_supply = 12; 
  driver2.init();
  motor2.linkDriver(&driver2);
  motor2.voltage_sensor_align = 1;    
  motor2.controller = MotionControlType::velocity; 
  //motor2.controller = MotionControlType::torque; 
  // contoller configuration 
  // default parameters in defaults.h
  // velocity PI controller parameters
  motor1.PID_velocity.P = 0.1;  
  motor1.PID_velocity.I = 1.0;   
  motor1.PID_velocity.D = 0.001; 
  motor1.LPF_velocity.Tf = 0.01; 
  motor1.PID_velocity.output_ramp = 1000; 
  motor2.PID_velocity.P = 0.1;  
  motor2.PID_velocity.I = 1.0;   
  motor2.PID_velocity.D = 0.001; 
  motor2.LPF_velocity.Tf = 0.01;  
  motor2.PID_velocity.output_ramp = 1000; 

  // use monitoring with serial 

  // comment out if not needed
  motor1.useMonitoring(Serial1);  
  motor2.useMonitoring(Serial1); 

  // initialize motor
  motor1.init();
  motor1.initFOC(4.19, Direction::CW); 
  motor2.init();
  motor2.initFOC(4.19, Direction::CW); 
  motor1.target = 1.0;
  motor2.target = -1.0;
  // add target command T

  //command.add('T', doTarget, "target vel");
  Serial1.println(F("Motor ready."));
  Serial1.println(F("Set the target velocity using serial terminal:"));
  //Serial.println(motor2.zero_electric_angle);
  //Serial.println(sensor2.direction);
  _delay(1000);

}

void serialReceiveUserCommand() {

  static String received_chars;
  while (Serial1.available()) {
    char inChar = (char)Serial1.read();
    received_chars += inChar;
    if (inChar == '\n') {
      target_velocity = received_chars.toFloat();
      get_velocity = motor2.shaftVelocity();
      Serial1.print("Get PID P value: ");
      Serial1.println(target_velocity);
      Serial1.print("motor vel is: ");
      Serial1.println(get_velocity);
      received_chars = "";
    }

  }

}

void loop() {

  // main FOC algorithm function
  // the faster you run this function the better
  // Arduino UNO loop  ~1kHz
  // Bluepill loop ~10kHz 
  motor1.loopFOC(); 
  motor2.loopFOC(); 

  //motor.PID_velocity.P = target_velocity;
  // Motion control function 
  // velocity, position or voltage (defined in motor.controller)
  // this function can be run at much lower frequency than loopFOC() function
  // You can also use motor.move() and set the motor.target in the code
  motor1.move(); //[rad/s] cca 50rpm
  motor2.move(); //[rad/s] cca 50rpm

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

}

MODULE MOTOR1 POWER

can you give me an email ?I can provide runing video, the whole project and code :grinning:

I dont need a video or the project. Let me read the code.
Arduino ide or platformio? i see you call arduino.h? platformio?
another question, if you run open loop in opposite directions do you get correct motor motion?

vscode + platformio, stm32 develop with arduino(like arudino_foc support Nucleo broad), I haven’t used open loop control, because the open loop did not work on nucleo stm32 in the early days. Now a single motor runs very smoothly. The dual motors lose control when one speed is positive and the other is negative, and the speed is the same as that of positive and negative. Works very good,

First of all, congrats for your awesome PCB I love it.
This is a very curious peoblem. I do not know what might be causing it really :smiley:

Which library version are you using?

I can suggest you few steps before you go to the closed loop mode:

  1. Could you please try the open loop and see if you can get them to go in opposite directions?
  2. Could you try only the sensors, removing the driver code completely and seeing if when spinning the motors separately the angle is read well on both sensors and both directions

Also few tips:

  • dont call the motor.shaftVelocity(), this function is intended to be called only once per loop and it sets the motor.shaft_velocity variable that you can use instead. When you call shaftVelocity multiple times the time in between calls is too small to calculate the discrete derivation and you get very noisy values.
  • I would suggest you to use the commander interface for all the serial communication, basically avoid using theserialReceiveUserCommand in addition to the commander. Because the comnader will be already calling the Serial.available() etc. And you can easily add the target setting and any other advanced stuff to the commander, you can see some examples in docs and in the library examples.

2.1.1 version, thanks for your suggestion, I will do it

当我将HallSensor.cpp 文件中 HallSensor::updateState() 函数中的 pulse_diff = 0; 屏蔽掉,两个电机就能独立控制了,后果不详… 你可以尝试一下7bad5fba6ef96004