Hi everyone
We are members of a university project team at University of Michigan, and we are trying to use the SimpleFOC code to control our motor.
We had to build our own board to work alongside the code, since the competition we are competing in requires that we do so. Attached is a schematic of our board below:
We went through the tutorial on the website, and we were on Step 2. Testing the driver + motor combination - open-loop. We used the code shown below:
// Open loop motor control example
#include <Arduino.h>
#include <SimpleFOC.h>
///////////////////////// Pin configuration - SETUP ////////////////////////
int hallA = 10;
int hallB = 11;
int hallC = 12;
// 21 for NEW
int PP = 21;
// Phase A
// Pin 3 - FTM1 CH0
// Pin 4 - FTM1 CH1
// Phase B
// Pin 6 - FTM0 CH4
// Pin 20 - FTM0 CH5
// Phase C
// Pin 2 - FTM3 CH0
// Pin 14 - FTM3 CH1
// int phA_h = 3;
// int phA_l = 4;
// int phB_h = 6;
// int phB_l = 20;
// int phC_h = 2;
// int phC_l = 14;
////////////////////////////////////////////////////////////////////////////
// Trying different configurations
// // Config 1
// int phA_h = 3;
// int phA_l = 4;
// int phB_h = 6;
// int phB_l = 20;
// int phC_h = 2;
// int phC_l = 14;
// // Config 2
// int phA_h = 3;
// int phA_l = 4;
// int phB_h = 2;
// int phB_l = 14;
// int phC_h = 6;
// int phC_l = 20;
// // Config 3
// int phA_h = 6;
// int phA_l = 20;
// int phB_h = 3;
// int phB_l = 4;
// int phC_h = 2;
// int phC_l = 14;
// HORRIBLE
// // Config 4
// int phA_h = 2;
// int phA_l = 14;
// int phB_h = 3;
// int phB_l = 4;
// int phC_h = 6;
// int phC_l = 20;
// best so far
// Config 5
int phA_h = 2;
int phA_l = 14;
int phB_h = 6;
int phB_l = 20;
int phC_h = 3;
int phC_l = 4;
// // Config 6
// int phA_h = 6;
// int phA_l = 20;
// int phB_h = 2;
// int phB_l = 14;
// int phC_h = 3;
// int phC_l = 4;
////////////////////////////////////////////////////////////////////////////
// BLDC motor & driver instance
// BLDCMotor motor = BLDCMotor(pole pair number);
BLDCMotor motor = BLDCMotor(PP);
// BLDCDriver3PWM driver = BLDCDriver3PWM(pwmA, pwmB, pwmC, Enable(optional));
BLDCDriver6PWM driver = BLDCDriver6PWM(phA_h, phA_l, phB_h, phB_l, phC_h, phC_l);
// Stepper motor & driver instance
// StepperMotor motor = StepperMotor(50);
// StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
// target variable
float target_velocity = 30;
void setup()
{
driver.pwm_frequency = 22000;
// driver config
// power supply voltage [V]
driver.voltage_power_supply = 40;
driver.voltage_limit = 40;
driver.init();
// link the motor and the driver
motor.linkDriver(&driver);
// limiting motor movements
motor.voltage_limit = 40; // [V]
motor.velocity_limit = 10; // [rad/s] cca 50rpm
// open loop control config
motor.controller = MotionControlType::velocity_openloop;
// enable driver
driver.enable();
// init motor hardware
motor.init();
Serial.begin(115200);
Serial.println("Motor ready!");
_delay(1000);
}
void loop()
{
// open loop velocity movement
// using motor.voltage_limit and motor.velocity_limit
motor.move(target_velocity);
// user communication
}
We also modified the hardware functions called in BLDCDriver6PWM::setPwm and int BLDCDriver6PWM::init(), shown below:
// init hardware pins
int BLDCDriver6PWM::init()
{
// PWM pins
pinMode(pwmA_h, OUTPUT);
pinMode(pwmB_h, OUTPUT);
pinMode(pwmC_h, OUTPUT);
pinMode(pwmA_l, OUTPUT);
pinMode(pwmB_l, OUTPUT);
pinMode(pwmC_l, OUTPUT);
if (_isset(enable_pin))
pinMode(enable_pin, OUTPUT);
// sanity check for the voltage limit configuration
if (!_isset(voltage_limit) || voltage_limit > voltage_power_supply)
voltage_limit = voltage_power_supply;
// configure 6pwm
// hardware specific function - depending on driver and mcu
return teensyconfigure6PWM();
}
// Set voltage to the pwm pin
void BLDCDriver6PWM::setPwm(float Ua, float Ub, float Uc)
{
// limit the voltage in driver
Ua = _constrain(Ua, 0, voltage_limit);
Ub = _constrain(Ub, 0, voltage_limit);
Uc = _constrain(Uc, 0, voltage_limit);
// calculate duty cycle
// limited in [0,1]
dc_a = _constrain(Ua / voltage_power_supply, 0.0f, 1.0f);
dc_b = _constrain(Ub / voltage_power_supply, 0.0f, 1.0f);
dc_c = _constrain(Uc / voltage_power_supply, 0.0f, 1.0f);
// hardware specific writing
// hardware specific function - depending on driver and mcu
// NEED TO EDIT teensy_mcu.cpp
teensywriteDutyCycle6PWM(dc_a, dc_b, dc_c);
}
int BLDCDriver6PWM::teensyconfigure6PWM()
{
// Set Write pwm_frequency
analogWriteFrequency(pwmA_h, pwm_frequency);
analogWriteFrequency(pwmA_l, pwm_frequency);
analogWriteFrequency(pwmB_h, pwm_frequency);
analogWriteFrequency(pwmB_l, pwm_frequency);
analogWriteFrequency(pwmC_h, pwm_frequency);
analogWriteFrequency(pwmC_l, pwm_frequency);
// Phase A
// Pin 3 - FTM1 CH0
// Pin 4 - FTM1 CH1
// Phase B
// Pin 6 - FTM0 CH4
// Pin 20 - FTM0 CH5
// Phase C
// Pin 2 - FTM3 CH0
// Pin 14 - FTM3 CH1
// Configure FTM1
int *status_FTM1 = (int *)0x40039000;
int *deadtime_FTM1 = (int *)0x40039068;
int *combine_FTM1 = (int *)0x40039064;
// configure center aligned PWM
*status_FTM1 = 0x00000008;
// inverting and deadtime insertion for FTM1
*combine_FTM1 = 0x00000012;
*deadtime_FTM1 = 0x00000093; // Deadtime: 1.294 microseconds
// Configure FTM0
int *status_FTM0 = (int *)0x40038000;
int *deadtime_FTM0 = (int *)0x40038068;
int *combine_FTM0 = (int *)0x40038064;
// // configure center aligned PWM
*status_FTM0 = 0x00000008;
// // inverting and deadtime insertion for FTM1
*combine_FTM0 = 0x00120000;
*deadtime_FTM0 = 0x00000093; // Deadtime: 1.294 microseconds
// Configure FTM3
int *status_FTM3 = (int *)0x400B9000;
int *deadtime_FTM3 = (int *)0x400B9068;
int *combine_FTM3 = (int *)0x400B9064;
// configure center aligned PWM
*status_FTM3 = 0x00000008;
// inverting and deadtime insertion for FTM1
*combine_FTM3 = 0x00000012;
*deadtime_FTM3 = 0x00000093; // Deadtime: 1.294 microseconds
}
int BLDCDriver6PWM::teensywriteDutyCycle6PWM(float dc_a, float dc_b, float dc_c)
{
analogWrite(pwmA_h, 255 * dc_a);
analogWrite(pwmA_l, 255 * dc_a);
analogWrite(pwmB_h, 255 * dc_b);
analogWrite(pwmB_l, 255 * dc_b);
analogWrite(pwmC_h, 255 * dc_c);
analogWrite(pwmC_l, 255 * dc_c);
}
Our motor is the U13Ⅱ Power Type UAV Motor KV65_U Power Type_U Type_Motors_Multi-rotor UAV Power_T-MOTOR Official Store-Multi-rotor UAV,Fixed Wing,VTOL,FPV and Robot Power.
We tried every combination of pins since we did not know what phases corresponded to each wire in our motor. However, our motor is failing to spin correctly. Attached is a link to a video:
Attached are our waveforms generated by each pin to the MOSFET, labeled AH (Phase A high) to CL (Phase C low).
Any help would be greatly appreciated! Thank you in advance!