Example open loop BLDC Motor doesn't spin, scope confirms

Newbie here, tried to get a brushless gimbal motor (2805 140KV) to spin in open loop with the g431 esc-1, but it simply won’t budge. I hooked up the motor wires to a scope and confirmed there was simply nothing coming out. I took the example code and just modified it slightly to use the builtin potentiometer instead of the commands.

Also, the motor’s data sheet says there’s 14 poles which means the pole pair value should be 7 right?

#include <SimpleFOC.h>

BLDCMotor motor = BLDCMotor(7);
BLDCDriver6PWM driver = BLDCDriver6PWM(A_PHASE_UH, A_PHASE_UL, A_PHASE_VH, A_PHASE_VL, A_PHASE_WH, A_PHASE_WL);

float target_velocity = 1.0;

Commander command = Commander(Serial);
void doTarget(char* cmd) { command.scalar(&target_velocity, cmd); }
void doLimit(char* cmd) { command.scalar(&motor.voltage_limit, cmd); }

void setup() {
  driver.voltage_power_supply = 16;
  driver.voltage_limit = 6;
  driver.init();

  motor.linkDriver(&driver);
  motor.voltage_limit = 3.0;
  motor.controller = MotionControlType::velocity_openloop;
  motor.init();

  command.add('T', doTarget, "target velocity");
  command.add('L', doLimit, "voltage limit");

  Serial.begin(115200);
  Serial.println("Motor ready!");
  Serial.println("Set target velocity [rad/s]");
  _delay(1000);
}

void loop() {
  int pot_val = analogRead(A_POTENTIOMETER);
  float target = pot_val / 1024.0 * 10;

  Serial.print("target: ");
  Serial.println(target);

  motor.move(target);
  command.run();
}

EDIT: I’ve missed the fact that I’m getting the following lines of output in the serial monitor when debugging is enabled:

MOT: Monitor enabled!
MOT: Init not possible, driver not initialized

According to this post, it seems that the pins for the driver are incorrect, however I used the ones straight from the example.

Hi @maxgallup ,

What environment are you using? Is this on PlatformIO or ArduinoIDE?

That’s right!

That post is about the Teensy microcontroller, it doesn’t apply to B-G431-ESC1. We have some other forum posts about the B-G431-ESC1, including extremely long ones with many code examples:

1 Like

Hey, I’m using PlatformIO.

I also just found out that there is a signal coming out of the phase wires (previously undetected due to oscilloscope misconfiguration). However, the motor still doesn’t spin and am still getting the error message MOT: Init not possible, driver not initialized.

By adding debug print statements in the library it seems that the driver is not calling the correcting initializiation code. Through the debug statements, it seems that BLDCDriver6PWM.cpp calls the generic _configure6PWM function found in generic_mcu.cpp instead of the hardware specific one which in the case of g431_esc-1 would be stm32_mcu.cpp. The generic driver exits immediately returning an error resulting in the driver being uninitialized.

I’m quite new to PlatformIO, but where does BLDCDriver6PWM.cpp know which hardware specific driver implementation to call? Seems like it’s simply not calling the intended one (stm32).

EDIT: Deleting the generic_mcu.cpp file made the driver call the correct hardware specific code, so no more error messages! Sadly however, the motor still doesn’t spin.

Oh, maybe you are missing a build flag -D ARDUINO_B_G431B_ESC1, which should be put into the platformio.ini file.

Could you share the whole .ini file?

1 Like

Oh, I didn’t know about that one! Will give it a try tomorrow, but this is what I’ve been using thus far.

[env:disco_b_g431b_esc1]
platform = ststm32
board = disco_b_g431b_esc1
framework = arduino

build_flags =
	-D PIO_FRAMEWORK_ARDUINO_NANOLIB_FLOAT_PRINTF

lib_deps =
	https://github.com/simplefoc/Arduino-FOC
	SPI
	Wire

Please add a:

lib_archive = false

to your platformio.ini…

2 Likes

I think if using the board definition for the ESC1 then the build flag should already be there, you don’t need to add it.

That was it! thanks so much!