try to fix submodule
This commit is contained in:
@@ -0,0 +1,109 @@
|
||||
/**
|
||||
* B-G431B-ESC1 position motion control example with encoder
|
||||
*
|
||||
*/
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
// Motor instance
|
||||
BLDCMotor motor = BLDCMotor(11);
|
||||
BLDCDriver6PWM driver = BLDCDriver6PWM(A_PHASE_UH, A_PHASE_UL, A_PHASE_VH, A_PHASE_VL, A_PHASE_WH, A_PHASE_WL);
|
||||
LowsideCurrentSense currentSense = LowsideCurrentSense(0.003f, -64.0f/7.0f, A_OP1_OUT, A_OP2_OUT, A_OP3_OUT);
|
||||
|
||||
|
||||
// encoder instance
|
||||
Encoder encoder = Encoder(A_HALL2, A_HALL3, 2048, A_HALL1);
|
||||
|
||||
// Interrupt routine intialisation
|
||||
// channel A and B callbacks
|
||||
void doA(){encoder.handleA();}
|
||||
void doB(){encoder.handleB();}
|
||||
void doIndex(){encoder.handleIndex();}
|
||||
|
||||
// instantiate the commander
|
||||
Commander command = Commander(Serial);
|
||||
void doTarget(char* cmd) { command.motion(&motor, cmd); }
|
||||
|
||||
void setup() {
|
||||
|
||||
// initialize encoder sensor hardware
|
||||
encoder.init();
|
||||
encoder.enableInterrupts(doA, doB);
|
||||
|
||||
// link the motor to the sensor
|
||||
motor.linkSensor(&encoder);
|
||||
|
||||
// driver config
|
||||
// power supply voltage [V]
|
||||
driver.voltage_power_supply = 12;
|
||||
driver.init();
|
||||
// link the motor and the driver
|
||||
motor.linkDriver(&driver);
|
||||
// link current sense and the driver
|
||||
currentSense.linkDriver(&driver);
|
||||
|
||||
// current sensing
|
||||
currentSense.init();
|
||||
// no need for aligning
|
||||
currentSense.skip_align = true;
|
||||
motor.linkCurrentSense(¤tSense);
|
||||
|
||||
// aligning voltage [V]
|
||||
motor.voltage_sensor_align = 3;
|
||||
// index search velocity [rad/s]
|
||||
motor.velocity_index_search = 3;
|
||||
|
||||
// set motion control loop to be used
|
||||
motor.controller = MotionControlType::velocity;
|
||||
|
||||
// contoller configuration
|
||||
// default parameters in defaults.h
|
||||
|
||||
// velocity PI controller parameters
|
||||
motor.PID_velocity.P = 0.2;
|
||||
motor.PID_velocity.I = 20;
|
||||
// default voltage_power_supply
|
||||
motor.voltage_limit = 6;
|
||||
// jerk control using voltage voltage ramp
|
||||
// default value is 300 volts per sec ~ 0.3V per millisecond
|
||||
motor.PID_velocity.output_ramp = 1000;
|
||||
|
||||
// velocity low pass filtering time constant
|
||||
motor.LPF_velocity.Tf = 0.01;
|
||||
|
||||
// angle P controller
|
||||
motor.P_angle.P = 20;
|
||||
// maximal velocity of the position control
|
||||
motor.velocity_limit = 4;
|
||||
|
||||
|
||||
// use monitoring with serial
|
||||
Serial.begin(115200);
|
||||
// comment out if not needed
|
||||
motor.useMonitoring(Serial);
|
||||
|
||||
// initialize motor
|
||||
motor.init();
|
||||
// align encoder and start FOC
|
||||
motor.initFOC();
|
||||
|
||||
// add target command T
|
||||
command.add('T', doTarget, "target angle");
|
||||
|
||||
Serial.println(F("Motor ready."));
|
||||
Serial.println(F("Set the target angle using serial terminal:"));
|
||||
_delay(1000);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// main FOC algorithm function
|
||||
|
||||
// Motion control function
|
||||
motor.move();
|
||||
|
||||
// function intended to be used with serial plotter to monitor motor variables
|
||||
// significantly slowing the execution down!!!!
|
||||
// motor.monitor();
|
||||
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1 @@
|
||||
-DHAL_OPAMP_MODULE_ENABLED
|
||||
@@ -0,0 +1,115 @@
|
||||
/**
|
||||
*
|
||||
* STM32 Bluepill position motion control example with encoder
|
||||
*
|
||||
* The same example can be ran with any STM32 board - just make sure that put right pin numbers.
|
||||
*
|
||||
*/
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
// Motor instance
|
||||
BLDCMotor motor = BLDCMotor(11);
|
||||
// BLDCDriver3PWM(IN1, IN2, IN3, enable(optional))
|
||||
BLDCDriver3PWM driver = BLDCDriver3PWM(PB6, PB7, PB8, PB5);
|
||||
// BLDCDriver6PWM(IN1_H, IN1_L, IN2_H, IN2_L, IN3_H, IN3_L, enable(optional))
|
||||
//BLDCDriver6PWM driver = BLDCDriver6PWM(PA8, PB13, PA9, PB14, PA10, PB15, PB12);
|
||||
|
||||
// encoder instance
|
||||
Encoder encoder = Encoder(PA8, PA9, 8192, PA10);
|
||||
|
||||
// Interrupt routine intialisation
|
||||
// channel A and B callbacks
|
||||
void doA(){encoder.handleA();}
|
||||
void doB(){encoder.handleB();}
|
||||
void doI(){encoder.handleIndex();}
|
||||
|
||||
|
||||
// angle set point variable
|
||||
float target_angle = 0;
|
||||
// instantiate the commander
|
||||
Commander command = Commander(Serial);
|
||||
void doTarget(char* cmd) { command.scalar(&target_angle, cmd); }
|
||||
|
||||
|
||||
void setup() {
|
||||
|
||||
// initialize encoder sensor hardware
|
||||
encoder.init();
|
||||
encoder.enableInterrupts(doA, doB, doI);
|
||||
// link the motor to the sensor
|
||||
motor.linkSensor(&encoder);
|
||||
|
||||
// driver config
|
||||
// power supply voltage [V]
|
||||
driver.voltage_power_supply = 12;
|
||||
driver.init();
|
||||
// link the motor and the driver
|
||||
motor.linkDriver(&driver);
|
||||
|
||||
// aligning voltage [V]
|
||||
motor.voltage_sensor_align = 3;
|
||||
// index search velocity [rad/s]
|
||||
motor.velocity_index_search = 3;
|
||||
|
||||
// set motion control loop to be used
|
||||
motor.controller = MotionControlType::velocity;
|
||||
|
||||
// contoller configuration
|
||||
// default parameters in defaults.h
|
||||
|
||||
// velocity PI controller parameters
|
||||
motor.PID_velocity.P = 0.2f;
|
||||
motor.PID_velocity.I = 20;
|
||||
// default voltage_power_supply
|
||||
motor.voltage_limit = 6;
|
||||
// jerk control using voltage voltage ramp
|
||||
// default value is 300 volts per sec ~ 0.3V per millisecond
|
||||
motor.PID_velocity.output_ramp = 1000;
|
||||
|
||||
// velocity low pass filtering time constant
|
||||
motor.LPF_velocity.Tf = 0.01f;
|
||||
|
||||
// angle P controller
|
||||
motor.P_angle.P = 20;
|
||||
// maximal velocity of the position control
|
||||
motor.velocity_limit = 4;
|
||||
|
||||
|
||||
// use monitoring with serial
|
||||
Serial.begin(115200);
|
||||
// comment out if not needed
|
||||
motor.useMonitoring(Serial);
|
||||
|
||||
// initialize motor
|
||||
motor.init();
|
||||
// align encoder and start FOC
|
||||
motor.initFOC();
|
||||
|
||||
// add target command T
|
||||
command.add('T', doTarget, "target angle");
|
||||
|
||||
Serial.println(F("Motor ready."));
|
||||
Serial.println(F("Set the target angle using serial terminal:"));
|
||||
_delay(1000);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// main FOC algorithm function
|
||||
// the faster you run this function the better
|
||||
// Arduino UNO loop ~1kHz
|
||||
// Bluepill loop ~10kHz
|
||||
motor.loopFOC();
|
||||
|
||||
// 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
|
||||
motor.move(target_angle);
|
||||
|
||||
// function intended to be used with serial plotter to monitor motor variables
|
||||
// significantly slowing the execution down!!!!
|
||||
// motor.monitor();
|
||||
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1,115 @@
|
||||
/**
|
||||
*
|
||||
* STM32 Bluepill position motion control example with magnetic sensor
|
||||
*
|
||||
* The same example can be ran with any STM32 board - just make sure that put right pin numbers.
|
||||
*
|
||||
*/
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
// SPI Magnetic sensor instance (AS5047U example)
|
||||
// MISO PA7
|
||||
// MOSI PA6
|
||||
// SCK PA5
|
||||
MagneticSensorSPI sensor = MagneticSensorSPI(PA4, 14, 0x3FFF);
|
||||
|
||||
// I2C Magnetic sensor instance (AS5600 example)
|
||||
// make sure to use the pull-ups!!
|
||||
// SDA PB7
|
||||
// SCL PB6
|
||||
//MagneticSensorI2C sensor = MagneticSensorI2C(0x36, 12, 0X0C, 4);
|
||||
|
||||
// Motor instance
|
||||
BLDCMotor motor = BLDCMotor(11);
|
||||
// BLDCDriver3PWM(IN1, IN2, IN3, enable(optional))
|
||||
BLDCDriver3PWM driver = BLDCDriver3PWM(PB6, PB7, PB8, PB5);
|
||||
// BLDCDriver6PWM(IN1_H, IN1_L, IN2_H, IN2_L, IN3_H, IN3_L, enable(optional))
|
||||
//BLDCDriver6PWM driver = BLDCDriver6PWM(PA8, PB13, PA9, PB14, PA10, PB15, PB12);
|
||||
|
||||
|
||||
// angle set point variable
|
||||
float target_angle = 0;
|
||||
// instantiate the commander
|
||||
Commander command = Commander(Serial);
|
||||
void doTarget(char* cmd) { command.scalar(&target_angle, cmd); }
|
||||
|
||||
|
||||
void setup() {
|
||||
|
||||
// initialise magnetic sensor hardware
|
||||
sensor.init();
|
||||
// link the motor to the sensor
|
||||
motor.linkSensor(&sensor);
|
||||
|
||||
// driver config
|
||||
// power supply voltage [V]
|
||||
driver.voltage_power_supply = 12;
|
||||
driver.init();
|
||||
// link the motor and the driver
|
||||
motor.linkDriver(&driver);
|
||||
|
||||
// choose FOC modulation (optional)
|
||||
motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
|
||||
|
||||
// set motion control loop to be used
|
||||
motor.controller = MotionControlType::angle;
|
||||
|
||||
// contoller configuration
|
||||
// default parameters in defaults.h
|
||||
|
||||
// velocity PI controller parameters
|
||||
motor.PID_velocity.P = 0.2f;
|
||||
motor.PID_velocity.I = 20;
|
||||
// maximal voltage to be set to the motor
|
||||
motor.voltage_limit = 6;
|
||||
|
||||
// velocity low pass filtering time constant
|
||||
// the lower the less filtered
|
||||
motor.LPF_velocity.Tf = 0.01f;
|
||||
|
||||
// angle P controller
|
||||
motor.P_angle.P = 20;
|
||||
// maximal velocity of the position control
|
||||
motor.velocity_limit = 40;
|
||||
|
||||
// use monitoring with serial
|
||||
Serial.begin(115200);
|
||||
// comment out if not needed
|
||||
motor.useMonitoring(Serial);
|
||||
|
||||
|
||||
// initialize motor
|
||||
motor.init();
|
||||
// align sensor and start FOC
|
||||
motor.initFOC();
|
||||
|
||||
// add target command T
|
||||
command.add('T', doTarget, "target angle");
|
||||
|
||||
Serial.println(F("Motor ready."));
|
||||
Serial.println(F("Set the target angle using serial terminal:"));
|
||||
_delay(1000);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
|
||||
// main FOC algorithm function
|
||||
// the faster you run this function the better
|
||||
// Arduino UNO loop ~1kHz
|
||||
// Bluepill loop ~10kHz
|
||||
motor.loopFOC();
|
||||
|
||||
// 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
|
||||
motor.move(target_angle);
|
||||
|
||||
|
||||
// function intended to be used with serial plotter to monitor motor variables
|
||||
// significantly slowing the execution down!!!!
|
||||
// motor.monitor();
|
||||
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1,130 @@
|
||||
/**
|
||||
* Comprehensive BLDC motor control example using encoder and the DRV8302 board
|
||||
*
|
||||
* Using serial terminal user can send motor commands and configure the motor and FOC in real-time:
|
||||
* - configure PID controller constants
|
||||
* - change motion control loops
|
||||
* - monitor motor variabels
|
||||
* - set target values
|
||||
* - check all the configuration values
|
||||
*
|
||||
* check the https://docs.simplefoc.com for full list of motor commands
|
||||
*
|
||||
*/
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
// DRV8302 pins connections
|
||||
// don't forget to connect the common ground pin
|
||||
#define INH_A 9
|
||||
#define INH_B 10
|
||||
#define INH_C 11
|
||||
|
||||
#define EN_GATE 7
|
||||
#define M_PWM A1
|
||||
#define M_OC A2
|
||||
#define OC_ADJ A3
|
||||
|
||||
// Motor instance
|
||||
BLDCMotor motor = BLDCMotor(11);
|
||||
BLDCDriver3PWM driver = BLDCDriver3PWM(INH_A, INH_B, INH_C, EN_GATE);
|
||||
|
||||
// encoder instance
|
||||
Encoder encoder = Encoder(2, 3, 8192);
|
||||
|
||||
// Interrupt routine intialisation
|
||||
// channel A and B callbacks
|
||||
void doA(){encoder.handleA();}
|
||||
void doB(){encoder.handleB();}
|
||||
|
||||
|
||||
// commander interface
|
||||
Commander command = Commander(Serial);
|
||||
void onMotor(char* cmd){ command.motor(&motor, cmd); }
|
||||
|
||||
void setup() {
|
||||
|
||||
// initialize encoder sensor hardware
|
||||
encoder.init();
|
||||
encoder.enableInterrupts(doA, doB);
|
||||
// link the motor to the sensor
|
||||
motor.linkSensor(&encoder);
|
||||
|
||||
// DRV8302 specific code
|
||||
// M_OC - enable overcurrent protection
|
||||
pinMode(M_OC,OUTPUT);
|
||||
digitalWrite(M_OC,LOW);
|
||||
// M_PWM - enable 3pwm mode
|
||||
pinMode(M_PWM,OUTPUT);
|
||||
digitalWrite(M_PWM,HIGH);
|
||||
// OD_ADJ - set the maximum overcurrent limit possible
|
||||
// Better option would be to use voltage divisor to set exact value
|
||||
pinMode(OC_ADJ,OUTPUT);
|
||||
digitalWrite(OC_ADJ,HIGH);
|
||||
|
||||
|
||||
// driver config
|
||||
// power supply voltage [V]
|
||||
driver.voltage_power_supply = 12;
|
||||
driver.init();
|
||||
// link the motor and the driver
|
||||
motor.linkDriver(&driver);
|
||||
|
||||
|
||||
// choose FOC modulation
|
||||
motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
|
||||
|
||||
// set control loop type to be used
|
||||
motor.controller = MotionControlType::torque;
|
||||
|
||||
// contoller configuration based on the controll type
|
||||
motor.PID_velocity.P = 0.2f;
|
||||
motor.PID_velocity.I = 20;
|
||||
// default voltage_power_supply
|
||||
motor.voltage_limit = 12;
|
||||
|
||||
// velocity low pass filtering time constant
|
||||
motor.LPF_velocity.Tf = 0.01f;
|
||||
|
||||
// angle loop controller
|
||||
motor.P_angle.P = 20;
|
||||
// angle loop velocity limit
|
||||
motor.velocity_limit = 50;
|
||||
|
||||
// use monitoring with serial for motor init
|
||||
// monitoring port
|
||||
Serial.begin(115200);
|
||||
// comment out if not needed
|
||||
motor.useMonitoring(Serial);
|
||||
|
||||
// initialise motor
|
||||
motor.init();
|
||||
// align encoder and start FOC
|
||||
motor.initFOC();
|
||||
|
||||
// set the inital target value
|
||||
motor.target = 2;
|
||||
|
||||
// define the motor id
|
||||
command.add('A', onMotor, "motor");
|
||||
|
||||
Serial.println(F("Full control example: "));
|
||||
Serial.println(F("Run user commands to configure and the motor (find the full command list in docs.simplefoc.com) \n "));
|
||||
Serial.println(F("Initial motion control loop is voltage loop."));
|
||||
Serial.println(F("Initial target voltage 2V."));
|
||||
|
||||
_delay(1000);
|
||||
}
|
||||
|
||||
|
||||
void loop() {
|
||||
// iterative setting FOC phase voltage
|
||||
motor.loopFOC();
|
||||
|
||||
// iterative function setting the outter loop target
|
||||
// velocity, position or voltage
|
||||
// if tatget not set in parameter uses motor.target variable
|
||||
motor.move();
|
||||
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1,129 @@
|
||||
/**
|
||||
* Comprehensive BLDC motor control example using encoder and the DRV8302 board
|
||||
*
|
||||
* Using serial terminal user can send motor commands and configure the motor and FOC in real-time:
|
||||
* - configure PID controller constants
|
||||
* - change motion control loops
|
||||
* - monitor motor variabels
|
||||
* - set target values
|
||||
* - check all the configuration values
|
||||
*
|
||||
* check the https://docs.simplefoc.com for full list of motor commands
|
||||
*
|
||||
*/
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
// DRV8302 pins connections
|
||||
// don't forget to connect the common ground pin
|
||||
#define INH_A 3
|
||||
#define INH_B 5
|
||||
#define INH_C 9
|
||||
#define INL_A 11
|
||||
#define INL_B 6
|
||||
#define INL_C 10
|
||||
|
||||
#define EN_GATE 7
|
||||
#define M_PWM A1
|
||||
#define M_OC A2
|
||||
#define OC_ADJ A3
|
||||
|
||||
// Motor instance
|
||||
BLDCMotor motor = BLDCMotor(11);
|
||||
BLDCDriver6PWM driver = BLDCDriver6PWM(INH_A,INH_A, INH_B,INH_B, INH_C,INL_C, EN_GATE);
|
||||
|
||||
// encoder instance
|
||||
Encoder encoder = Encoder(2, 3, 8192);
|
||||
|
||||
// Interrupt routine intialisation
|
||||
// channel A and B callbacks
|
||||
void doA(){encoder.handleA();}
|
||||
void doB(){encoder.handleB();}
|
||||
|
||||
|
||||
// commander interface
|
||||
Commander command = Commander(Serial);
|
||||
void onMotor(char* cmd){ command.motor(&motor, cmd); }
|
||||
|
||||
void setup() {
|
||||
|
||||
// initialize encoder sensor hardware
|
||||
encoder.init();
|
||||
encoder.enableInterrupts(doA, doB);
|
||||
// link the motor to the sensor
|
||||
motor.linkSensor(&encoder);
|
||||
|
||||
// DRV8302 specific code
|
||||
// M_OC - enable overcurrent protection
|
||||
pinMode(M_OC,OUTPUT);
|
||||
digitalWrite(M_OC,LOW);
|
||||
// M_PWM - disable 3pwm mode
|
||||
pinMode(M_PWM,OUTPUT);
|
||||
digitalWrite(M_PWM, LOW);
|
||||
// OD_ADJ - set the maximum overcurrent limit possible
|
||||
// Better option would be to use voltage divisor to set exact value
|
||||
pinMode(OC_ADJ,OUTPUT);
|
||||
digitalWrite(OC_ADJ,HIGH);
|
||||
|
||||
// driver config
|
||||
// power supply voltage [V]
|
||||
driver.voltage_power_supply = 12;
|
||||
driver.init();
|
||||
// link the motor and the driver
|
||||
motor.linkDriver(&driver);
|
||||
|
||||
// choose FOC modulation
|
||||
motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
|
||||
|
||||
// set control loop type to be used
|
||||
motor.controller = MotionControlType::torque;
|
||||
|
||||
// contoller configuration based on the controll type
|
||||
motor.PID_velocity.P = 0.2f;
|
||||
motor.PID_velocity.I = 20;
|
||||
// default voltage_power_supply
|
||||
motor.voltage_limit = 12;
|
||||
|
||||
// velocity low pass filtering time constant
|
||||
motor.LPF_velocity.Tf = 0.01f;
|
||||
|
||||
// angle loop controller
|
||||
motor.P_angle.P = 20;
|
||||
// angle loop velocity limit
|
||||
motor.velocity_limit = 50;
|
||||
|
||||
// use monitoring with serial for motor init
|
||||
// monitoring port
|
||||
Serial.begin(115200);
|
||||
// comment out if not needed
|
||||
motor.useMonitoring(Serial);
|
||||
|
||||
// initialise motor
|
||||
motor.init();
|
||||
// align encoder and start FOC
|
||||
motor.initFOC();
|
||||
|
||||
// set the inital target value
|
||||
motor.target = 2;
|
||||
|
||||
// define the motor id
|
||||
command.add('M', onMotor, "motor");
|
||||
|
||||
Serial.println(F("Initial motion control loop is voltage loop."));
|
||||
Serial.println(F("Initial target voltage 2V."));
|
||||
|
||||
_delay(1000);
|
||||
}
|
||||
|
||||
|
||||
void loop() {
|
||||
// iterative setting FOC phase voltage
|
||||
motor.loopFOC();
|
||||
|
||||
// iterative function setting the outter loop target
|
||||
// velocity, position or voltage
|
||||
// if tatget not set in parameter uses motor.target variable
|
||||
motor.move();
|
||||
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1,167 @@
|
||||
/**
|
||||
* Comprehensive BLDC motor control example using encoder and the DRV8302 board
|
||||
*
|
||||
* Using serial terminal user can send motor commands and configure the motor and FOC in real-time:
|
||||
* - configure PID controller constants
|
||||
* - change motion control loops
|
||||
* - monitor motor variabels
|
||||
* - set target values
|
||||
* - check all the configuration values
|
||||
*
|
||||
* check the https://docs.simplefoc.com for full list of motor commands
|
||||
*
|
||||
*/
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
// DRV8302 pins connections
|
||||
// don't forget to connect the common ground pin
|
||||
#define INH_A 21
|
||||
#define INH_B 19
|
||||
#define INH_C 18
|
||||
|
||||
#define EN_GATE 5
|
||||
#define M_PWM 25
|
||||
#define M_OC 26
|
||||
#define OC_ADJ 12
|
||||
#define OC_GAIN 14
|
||||
|
||||
#define IOUTA 34
|
||||
#define IOUTB 35
|
||||
#define IOUTC 32
|
||||
|
||||
// Motor instance
|
||||
BLDCMotor motor = BLDCMotor(7);
|
||||
BLDCDriver3PWM driver = BLDCDriver3PWM(INH_A, INH_B, INH_C, EN_GATE);
|
||||
|
||||
// DRV8302 board has 0.005Ohm shunt resistors and the gain of 12.22 V/V
|
||||
LowsideCurrentSense cs = LowsideCurrentSense(0.005f, 12.22f, IOUTA, IOUTB, IOUTC);
|
||||
|
||||
// encoder instance
|
||||
Encoder encoder = Encoder(22, 23, 500);
|
||||
|
||||
// Interrupt routine intialisation
|
||||
// channel A and B callbacks
|
||||
void doA(){encoder.handleA();}
|
||||
void doB(){encoder.handleB();}
|
||||
|
||||
|
||||
// commander interface
|
||||
Commander command = Commander(Serial);
|
||||
void onMotor(char* cmd){ command.motor(&motor, cmd); }
|
||||
|
||||
void setup() {
|
||||
|
||||
// initialize encoder sensor hardware
|
||||
encoder.init();
|
||||
encoder.enableInterrupts(doA, doB);
|
||||
// link the motor to the sensor
|
||||
motor.linkSensor(&encoder);
|
||||
|
||||
// DRV8302 specific code
|
||||
// M_OC - enable overcurrent protection
|
||||
pinMode(M_OC,OUTPUT);
|
||||
digitalWrite(M_OC,LOW);
|
||||
// M_PWM - enable 3pwm mode
|
||||
pinMode(M_PWM,OUTPUT);
|
||||
digitalWrite(M_PWM,HIGH);
|
||||
// OD_ADJ - set the maximum overcurrent limit possible
|
||||
// Better option would be to use voltage divisor to set exact value
|
||||
pinMode(OC_ADJ,OUTPUT);
|
||||
digitalWrite(OC_ADJ,HIGH);
|
||||
pinMode(OC_GAIN,OUTPUT);
|
||||
digitalWrite(OC_GAIN,LOW);
|
||||
|
||||
|
||||
// driver config
|
||||
// power supply voltage [V]
|
||||
driver.voltage_power_supply = 12;
|
||||
driver.pwm_frequency = 15000;
|
||||
driver.init();
|
||||
// link the motor and the driver
|
||||
motor.linkDriver(&driver);
|
||||
// link current sense and the driver
|
||||
cs.linkDriver(&driver);
|
||||
|
||||
// align voltage
|
||||
motor.voltage_sensor_align = 0.5;
|
||||
|
||||
// control loop type and torque mode
|
||||
motor.torque_controller = TorqueControlType::voltage;
|
||||
motor.controller = MotionControlType::torque;
|
||||
motor.motion_downsample = 0.0;
|
||||
|
||||
// velocity loop PID
|
||||
motor.PID_velocity.P = 0.2;
|
||||
motor.PID_velocity.I = 5.0;
|
||||
// Low pass filtering time constant
|
||||
motor.LPF_velocity.Tf = 0.02;
|
||||
// angle loop PID
|
||||
motor.P_angle.P = 20.0;
|
||||
// Low pass filtering time constant
|
||||
motor.LPF_angle.Tf = 0.0;
|
||||
// current q loop PID
|
||||
motor.PID_current_q.P = 3.0;
|
||||
motor.PID_current_q.I = 100.0;
|
||||
// Low pass filtering time constant
|
||||
motor.LPF_current_q.Tf = 0.02;
|
||||
// current d loop PID
|
||||
motor.PID_current_d.P = 3.0;
|
||||
motor.PID_current_d.I = 100.0;
|
||||
// Low pass filtering time constant
|
||||
motor.LPF_current_d.Tf = 0.02;
|
||||
|
||||
// Limits
|
||||
motor.velocity_limit = 100.0; // 100 rad/s velocity limit
|
||||
motor.voltage_limit = 12.0; // 12 Volt limit
|
||||
motor.current_limit = 2.0; // 2 Amp current limit
|
||||
|
||||
|
||||
// use monitoring with serial for motor init
|
||||
// monitoring port
|
||||
Serial.begin(115200);
|
||||
// comment out if not needed
|
||||
motor.useMonitoring(Serial);
|
||||
motor.monitor_variables = _MON_CURR_Q | _MON_CURR_D; // monitor the two currents d and q
|
||||
motor.monitor_downsample = 1000;
|
||||
|
||||
// initialise motor
|
||||
motor.init();
|
||||
|
||||
cs.init();
|
||||
// driver 8302 has inverted gains on all channels
|
||||
cs.gain_a *=-1;
|
||||
cs.gain_b *=-1;
|
||||
cs.gain_c *=-1;
|
||||
motor.linkCurrentSense(&cs);
|
||||
|
||||
// align encoder and start FOC
|
||||
motor.initFOC();
|
||||
|
||||
// set the inital target value
|
||||
motor.target = 0;
|
||||
|
||||
// define the motor id
|
||||
command.add('M', onMotor, "motor");
|
||||
|
||||
Serial.println(F("Full control example: "));
|
||||
Serial.println(F("Run user commands to configure and the motor (find the full command list in docs.simplefoc.com) \n "));
|
||||
Serial.println(F("Initial motion control loop is voltage loop."));
|
||||
Serial.println(F("Initial target voltage 2V."));
|
||||
|
||||
_delay(1000);
|
||||
}
|
||||
|
||||
|
||||
void loop() {
|
||||
// iterative setting FOC phase voltage
|
||||
motor.loopFOC();
|
||||
|
||||
// iterative function setting the outter loop target
|
||||
motor.move();
|
||||
|
||||
// monitoring the state variables
|
||||
motor.monitor();
|
||||
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1,167 @@
|
||||
/**
|
||||
* Comprehensive BLDC motor control example using encoder and the DRV8302 board
|
||||
*
|
||||
* Using serial terminal user can send motor commands and configure the motor and FOC in real-time:
|
||||
* - configure PID controller constants
|
||||
* - change motion control loops
|
||||
* - monitor motor variabels
|
||||
* - set target values
|
||||
* - check all the configuration values
|
||||
*
|
||||
* check the https://docs.simplefoc.com for full list of motor commands
|
||||
*
|
||||
*/
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
// DRV8302 pins connections
|
||||
// don't forget to connect the common ground pin
|
||||
#define INH_A PA8
|
||||
#define INH_B PA9
|
||||
#define INH_C PA10
|
||||
|
||||
#define EN_GATE PB7
|
||||
#define M_PWM PB4
|
||||
#define M_OC PB3
|
||||
#define OC_ADJ PB6
|
||||
#define OC_GAIN PB5
|
||||
|
||||
#define IOUTA PA0
|
||||
#define IOUTB PA1
|
||||
#define IOUTC PA2
|
||||
|
||||
// Motor instance
|
||||
BLDCMotor motor = BLDCMotor(7);
|
||||
BLDCDriver3PWM driver = BLDCDriver3PWM(INH_A, INH_B, INH_C, EN_GATE);
|
||||
|
||||
// DRV8302 board has 0.005Ohm shunt resistors and the gain of 12.22 V/V
|
||||
LowsideCurrentSense cs = LowsideCurrentSense(0.005f, 12.22f, IOUTA, IOUTB, IOUTC);
|
||||
|
||||
// encoder instance
|
||||
Encoder encoder = Encoder(PB14, PB15, 2048);
|
||||
|
||||
// Interrupt routine intialisation
|
||||
// channel A and B callbacks
|
||||
void doA(){encoder.handleA();}
|
||||
void doB(){encoder.handleB();}
|
||||
|
||||
|
||||
// commander interface
|
||||
Commander command = Commander(Serial);
|
||||
void onMotor(char* cmd){ command.motor(&motor, cmd); }
|
||||
|
||||
void setup() {
|
||||
|
||||
// initialize encoder sensor hardware
|
||||
encoder.init();
|
||||
encoder.enableInterrupts(doA, doB);
|
||||
// link the motor to the sensor
|
||||
motor.linkSensor(&encoder);
|
||||
|
||||
// DRV8302 specific code
|
||||
// M_OC - enable overcurrent protection
|
||||
pinMode(M_OC,OUTPUT);
|
||||
digitalWrite(M_OC,LOW);
|
||||
// M_PWM - enable 3pwm mode
|
||||
pinMode(M_PWM,OUTPUT);
|
||||
digitalWrite(M_PWM,HIGH);
|
||||
// OD_ADJ - set the maximum overcurrent limit possible
|
||||
// Better option would be to use voltage divisor to set exact value
|
||||
pinMode(OC_ADJ,OUTPUT);
|
||||
digitalWrite(OC_ADJ,HIGH);
|
||||
pinMode(OC_GAIN,OUTPUT);
|
||||
digitalWrite(OC_GAIN,LOW);
|
||||
|
||||
|
||||
// driver config
|
||||
// power supply voltage [V]
|
||||
driver.voltage_power_supply = 19;
|
||||
driver.pwm_frequency = 15000; // suggested under 18khz
|
||||
driver.init();
|
||||
// link the motor and the driver
|
||||
motor.linkDriver(&driver);
|
||||
// link current sense and the driver
|
||||
cs.linkDriver(&driver);
|
||||
|
||||
// align voltage
|
||||
motor.voltage_sensor_align = 0.5;
|
||||
|
||||
// control loop type and torque mode
|
||||
motor.torque_controller = TorqueControlType::voltage;
|
||||
motor.controller = MotionControlType::torque;
|
||||
motor.motion_downsample = 0.0;
|
||||
|
||||
// velocity loop PID
|
||||
motor.PID_velocity.P = 0.2;
|
||||
motor.PID_velocity.I = 5.0;
|
||||
// Low pass filtering time constant
|
||||
motor.LPF_velocity.Tf = 0.02;
|
||||
// angle loop PID
|
||||
motor.P_angle.P = 20.0;
|
||||
// Low pass filtering time constant
|
||||
motor.LPF_angle.Tf = 0.0;
|
||||
// current q loop PID
|
||||
motor.PID_current_q.P = 3.0;
|
||||
motor.PID_current_q.I = 100.0;
|
||||
// Low pass filtering time constant
|
||||
motor.LPF_current_q.Tf = 0.02;
|
||||
// current d loop PID
|
||||
motor.PID_current_d.P = 3.0;
|
||||
motor.PID_current_d.I = 100.0;
|
||||
// Low pass filtering time constant
|
||||
motor.LPF_current_d.Tf = 0.02;
|
||||
|
||||
// Limits
|
||||
motor.velocity_limit = 100.0; // 100 rad/s velocity limit
|
||||
motor.voltage_limit = 12.0; // 12 Volt limit
|
||||
motor.current_limit = 2.0; // 2 Amp current limit
|
||||
|
||||
|
||||
// use monitoring with serial for motor init
|
||||
// monitoring port
|
||||
Serial.begin(115200);
|
||||
// comment out if not needed
|
||||
motor.useMonitoring(Serial);
|
||||
motor.monitor_variables = _MON_CURR_Q | _MON_CURR_D; // monitor the two currents d and q
|
||||
motor.monitor_downsample = 0;
|
||||
|
||||
// initialise motor
|
||||
motor.init();
|
||||
|
||||
cs.init();
|
||||
// driver 8302 has inverted gains on all channels
|
||||
cs.gain_a *=-1;
|
||||
cs.gain_b *=-1;
|
||||
cs.gain_c *=-1;
|
||||
motor.linkCurrentSense(&cs);
|
||||
|
||||
// align encoder and start FOC
|
||||
motor.initFOC();
|
||||
|
||||
// set the inital target value
|
||||
motor.target = 0;
|
||||
|
||||
// define the motor id
|
||||
command.add('M', onMotor, "motor");
|
||||
|
||||
Serial.println(F("Full control example: "));
|
||||
Serial.println(F("Run user commands to configure and the motor (find the full command list in docs.simplefoc.com) \n "));
|
||||
Serial.println(F("Initial motion control loop is voltage loop."));
|
||||
Serial.println(F("Initial target voltage 2V."));
|
||||
|
||||
_delay(1000);
|
||||
}
|
||||
|
||||
|
||||
void loop() {
|
||||
// iterative setting FOC phase voltage
|
||||
motor.loopFOC();
|
||||
|
||||
// iterative function setting the outter loop target
|
||||
motor.move();
|
||||
|
||||
// monitoring the state variables
|
||||
motor.monitor();
|
||||
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1,107 @@
|
||||
/**
|
||||
* ESP32 position motion control example with encoder
|
||||
*
|
||||
*/
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
// Motor instance
|
||||
BLDCMotor motor = BLDCMotor(11);
|
||||
BLDCDriver3PWM driver = BLDCDriver3PWM(25, 26, 27, 7);
|
||||
|
||||
// encoder instance
|
||||
Encoder encoder = Encoder(4, 2, 1024);
|
||||
|
||||
// Interrupt routine intialisation
|
||||
// channel A and B callbacks
|
||||
void doA(){encoder.handleA();}
|
||||
void doB(){encoder.handleB();}
|
||||
|
||||
// angle set point variable
|
||||
float target_angle = 0;
|
||||
// instantiate the commander
|
||||
Commander command = Commander(Serial);
|
||||
void doTarget(char* cmd) { command.scalar(&target_angle, cmd); }
|
||||
|
||||
void setup() {
|
||||
|
||||
// initialize encoder sensor hardware
|
||||
encoder.init();
|
||||
encoder.enableInterrupts(doA, doB);
|
||||
|
||||
// link the motor to the sensor
|
||||
motor.linkSensor(&encoder);
|
||||
|
||||
// driver config
|
||||
// power supply voltage [V]
|
||||
driver.voltage_power_supply = 12;
|
||||
driver.init();
|
||||
// link the motor and the driver
|
||||
motor.linkDriver(&driver);
|
||||
|
||||
// aligning voltage [V]
|
||||
motor.voltage_sensor_align = 3;
|
||||
// index search velocity [rad/s]
|
||||
motor.velocity_index_search = 3;
|
||||
|
||||
// set motion control loop to be used
|
||||
motor.controller = MotionControlType::velocity;
|
||||
|
||||
// contoller configuration
|
||||
// default parameters in defaults.h
|
||||
|
||||
// velocity PI controller parameters
|
||||
motor.PID_velocity.P = 0.2f;
|
||||
motor.PID_velocity.I = 20;
|
||||
// default voltage_power_supply
|
||||
motor.voltage_limit = 6;
|
||||
// jerk control using voltage voltage ramp
|
||||
// default value is 300 volts per sec ~ 0.3V per millisecond
|
||||
motor.PID_velocity.output_ramp = 1000;
|
||||
|
||||
// velocity low pass filtering time constant
|
||||
motor.LPF_velocity.Tf = 0.01f;
|
||||
|
||||
// angle P controller
|
||||
motor.P_angle.P = 20;
|
||||
// maximal velocity of the position control
|
||||
motor.velocity_limit = 4;
|
||||
|
||||
|
||||
// use monitoring with serial
|
||||
Serial.begin(115200);
|
||||
// comment out if not needed
|
||||
motor.useMonitoring(Serial);
|
||||
|
||||
// initialize motor
|
||||
motor.init();
|
||||
// align encoder and start FOC
|
||||
motor.initFOC();
|
||||
|
||||
// add target command T
|
||||
command.add('T', doTarget, "target angle");
|
||||
|
||||
Serial.println(F("Motor ready."));
|
||||
Serial.println(F("Set the target angle using serial terminal:"));
|
||||
_delay(1000);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// main FOC algorithm function
|
||||
// the faster you run this function the better
|
||||
// Arduino UNO loop ~1kHz
|
||||
// Bluepill loop ~10kHz
|
||||
motor.loopFOC();
|
||||
|
||||
// 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
|
||||
motor.move(target_angle);
|
||||
|
||||
// function intended to be used with serial plotter to monitor motor variables
|
||||
// significantly slowing the execution down!!!!
|
||||
// motor.monitor();
|
||||
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1,112 @@
|
||||
/**
|
||||
* ESP32 position motion control example with magnetic sensor
|
||||
*/
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
// SPI Magnetic sensor instance (AS5047U example)
|
||||
// MISO 12
|
||||
// MOSI 9
|
||||
// SCK 14
|
||||
// magnetic sensor instance - SPI
|
||||
MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, 15);
|
||||
|
||||
// I2C Magnetic sensor instance (AS5600 example)
|
||||
// make sure to use the pull-ups!!
|
||||
// SDA 21
|
||||
// SCL 22
|
||||
// magnetic sensor instance - I2C
|
||||
//MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);
|
||||
|
||||
// Analog output Magnetic sensor instance (AS5600)
|
||||
// MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020);
|
||||
|
||||
// Motor instance
|
||||
BLDCMotor motor = BLDCMotor(11);
|
||||
BLDCDriver3PWM driver = BLDCDriver3PWM(25, 26, 27, 7);
|
||||
|
||||
|
||||
// angle set point variable
|
||||
float target_angle = 0;
|
||||
// instantiate the commander
|
||||
Commander command = Commander(Serial);
|
||||
void doTarget(char* cmd) { command.scalar(&target_angle, cmd); }
|
||||
|
||||
void setup() {
|
||||
|
||||
// initialise magnetic sensor hardware
|
||||
sensor.init();
|
||||
// link the motor to the sensor
|
||||
motor.linkSensor(&sensor);
|
||||
|
||||
// driver config
|
||||
// power supply voltage [V]
|
||||
driver.voltage_power_supply = 12;
|
||||
driver.init();
|
||||
// link the motor and the driver
|
||||
motor.linkDriver(&driver);
|
||||
|
||||
// choose FOC modulation (optional)
|
||||
motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
|
||||
|
||||
// set motion control loop to be used
|
||||
motor.controller = MotionControlType::angle;
|
||||
|
||||
// contoller configuration
|
||||
// default parameters in defaults.h
|
||||
|
||||
// velocity PI controller parameters
|
||||
motor.PID_velocity.P = 0.2f;
|
||||
motor.PID_velocity.I = 20;
|
||||
// maximal voltage to be set to the motor
|
||||
motor.voltage_limit = 6;
|
||||
|
||||
// velocity low pass filtering time constant
|
||||
// the lower the less filtered
|
||||
motor.LPF_velocity.Tf = 0.01f;
|
||||
|
||||
// angle P controller
|
||||
motor.P_angle.P = 20;
|
||||
// maximal velocity of the position control
|
||||
motor.velocity_limit = 40;
|
||||
|
||||
// use monitoring with serial
|
||||
Serial.begin(115200);
|
||||
// comment out if not needed
|
||||
motor.useMonitoring(Serial);
|
||||
|
||||
|
||||
// initialize motor
|
||||
motor.init();
|
||||
// align sensor and start FOC
|
||||
motor.initFOC();
|
||||
|
||||
// add target command T
|
||||
command.add('T', doTarget, "target angle");
|
||||
|
||||
Serial.println(F("Motor ready."));
|
||||
Serial.println(F("Set the target angle using serial terminal:"));
|
||||
_delay(1000);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
|
||||
// main FOC algorithm function
|
||||
// the faster you run this function the better
|
||||
// Arduino UNO loop ~1kHz
|
||||
// Bluepill loop ~10kHz
|
||||
motor.loopFOC();
|
||||
|
||||
// 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
|
||||
motor.move(target_angle);
|
||||
|
||||
|
||||
// function intended to be used with serial plotter to monitor motor variables
|
||||
// significantly slowing the execution down!!!!
|
||||
// motor.monitor();
|
||||
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1,127 @@
|
||||
/**
|
||||
*
|
||||
* HMBGC position motion control example with encoder
|
||||
*
|
||||
* - Motor is connected the MOT1 connector (MOT1 9,10,11; MOT2 3,5,6)
|
||||
* - Encoder is connected to A0 and A1
|
||||
*
|
||||
* This board doesn't have any interrupt pins so we need to run all the encoder channels with the software interrupt library
|
||||
* - For this example we use: PciManager library : https://github.com/prampec/arduino-pcimanager
|
||||
*
|
||||
* See docs.simplefoc.com for more info.
|
||||
*
|
||||
*/
|
||||
#include <SimpleFOC.h>
|
||||
// software interrupt library
|
||||
#include <PciManager.h>
|
||||
#include <PciListenerImp.h>
|
||||
|
||||
|
||||
// BLDC motor & driver instance
|
||||
BLDCMotor motor = BLDCMotor(11);
|
||||
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 10, 11);
|
||||
|
||||
// encoder instance
|
||||
Encoder encoder = Encoder(A0, A1, 2048);
|
||||
|
||||
// Interrupt routine intialisation
|
||||
// channel A and B callbacks
|
||||
void doA(){encoder.handleA();}
|
||||
void doB(){encoder.handleB();}
|
||||
|
||||
// encoder interrupt init
|
||||
PciListenerImp listenerA(encoder.pinA, doA);
|
||||
PciListenerImp listenerB(encoder.pinB, doB);
|
||||
|
||||
|
||||
// angle set point variable
|
||||
float target_angle = 0;
|
||||
// instantiate the commander
|
||||
Commander command = Commander(Serial);
|
||||
void doTarget(char* cmd) { command.scalar(&target_angle, cmd); }
|
||||
|
||||
void setup() {
|
||||
|
||||
// initialise encoder hardware
|
||||
encoder.init();
|
||||
// interrupt initialization
|
||||
PciManager.registerListener(&listenerA);
|
||||
PciManager.registerListener(&listenerB);
|
||||
// link the motor to the sensor
|
||||
motor.linkSensor(&encoder);
|
||||
|
||||
// driver config
|
||||
// power supply voltage [V]
|
||||
driver.voltage_power_supply = 12;
|
||||
driver.init();
|
||||
// link the motor and the driver
|
||||
motor.linkDriver(&driver);
|
||||
|
||||
// aligning voltage [V]
|
||||
motor.voltage_sensor_align = 3;
|
||||
// index search velocity [rad/s]
|
||||
motor.velocity_index_search = 3;
|
||||
|
||||
// set motion control loop to be used
|
||||
motor.controller = MotionControlType::angle;
|
||||
|
||||
// contoller configuration
|
||||
// default parameters in defaults.h
|
||||
|
||||
// velocity PI controller parameters
|
||||
motor.PID_velocity.P = 0.2f;
|
||||
motor.PID_velocity.I = 20;
|
||||
// default voltage_power_supply
|
||||
motor.voltage_limit = 6;
|
||||
// jerk control using voltage voltage ramp
|
||||
// default value is 300 volts per sec ~ 0.3V per millisecond
|
||||
motor.PID_velocity.output_ramp = 1000;
|
||||
|
||||
// velocity low pass filtering time constant
|
||||
motor.LPF_velocity.Tf = 0.01f;
|
||||
|
||||
// angle P controller
|
||||
motor.P_angle.P = 20;
|
||||
// maximal velocity of the position control
|
||||
motor.velocity_limit = 4;
|
||||
|
||||
|
||||
// use monitoring with serial
|
||||
Serial.begin(115200);
|
||||
// comment out if not needed
|
||||
motor.useMonitoring(Serial);
|
||||
|
||||
// initialize motor
|
||||
motor.init();
|
||||
// align encoder and start FOC
|
||||
motor.initFOC();
|
||||
|
||||
// add target command T
|
||||
command.add('T', doTarget, "target angle");
|
||||
|
||||
Serial.println(F("Motor ready."));
|
||||
Serial.println(F("Set the target angle using serial terminal:"));
|
||||
_delay(1000);
|
||||
}
|
||||
|
||||
|
||||
void loop() {
|
||||
// main FOC algorithm function
|
||||
// the faster you run this function the better
|
||||
// Arduino UNO loop ~1kHz
|
||||
// Bluepill loop ~10kHz
|
||||
motor.loopFOC();
|
||||
|
||||
// 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
|
||||
motor.move(target_angle);
|
||||
|
||||
// function intended to be used with serial plotter to monitor motor variables
|
||||
// significantly slowing the execution down!!!!
|
||||
// motor.monitor();
|
||||
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1,110 @@
|
||||
/**
|
||||
*
|
||||
* HMBGC torque control example using voltage control loop.
|
||||
*
|
||||
* - Motor is connected the MOT1 connector (MOT1 9,10,11; MOT2 3,5,6)
|
||||
* - Encoder is connected to A0 and A1
|
||||
*
|
||||
* Most of the low-end BLDC driver boards doesn't have current measurement therefore SimpleFOC offers
|
||||
* you a way to control motor torque by setting the voltage to the motor instead hte current.
|
||||
*
|
||||
* This makes the BLDC motor effectively a DC motor, and you can use it in a same way. position motion control example with encoder
|
||||
*
|
||||
* NOTE:
|
||||
* > HMBGC doesn't have any interrupt pins so we need to run all the encoder channels with the software interrupt library
|
||||
* > - For this example we use: PciManager library : https://github.com/prampec/arduino-pcimanager
|
||||
*
|
||||
* See docs.simplefoc.com for more info.
|
||||
*
|
||||
*/
|
||||
#include <SimpleFOC.h>
|
||||
// software interrupt library
|
||||
#include <PciManager.h>
|
||||
#include <PciListenerImp.h>
|
||||
|
||||
|
||||
// BLDC motor & driver instance
|
||||
BLDCMotor motor = BLDCMotor(11);
|
||||
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 10, 11);
|
||||
|
||||
// encoder instance
|
||||
Encoder encoder = Encoder(A0, A1, 8192);
|
||||
|
||||
// Interrupt routine intialisation
|
||||
// channel A and B callbacks
|
||||
void doA(){encoder.handleA();}
|
||||
void doB(){encoder.handleB();}
|
||||
|
||||
// encoder interrupt init
|
||||
PciListenerImp listenerA(encoder.pinA, doA);
|
||||
PciListenerImp listenerB(encoder.pinB, doB);
|
||||
|
||||
|
||||
// voltage set point variable
|
||||
float target_voltage = 2;
|
||||
// instantiate the commander
|
||||
Commander command = Commander(Serial);
|
||||
void doTarget(char* cmd) { command.scalar(&target_voltage, cmd); }
|
||||
|
||||
void setup() {
|
||||
|
||||
// initialize encoder sensor hardware
|
||||
encoder.init();
|
||||
// interrupt initialization
|
||||
PciManager.registerListener(&listenerA);
|
||||
PciManager.registerListener(&listenerB);
|
||||
// link the motor to the sensor
|
||||
motor.linkSensor(&encoder);
|
||||
|
||||
// driver config
|
||||
// power supply voltage [V]
|
||||
driver.voltage_power_supply = 12;
|
||||
driver.init();
|
||||
// link the motor and the driver
|
||||
motor.linkDriver(&driver);
|
||||
|
||||
// choose FOC modulation (optional)
|
||||
motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
|
||||
|
||||
// set motion control loop to be used
|
||||
motor.controller = MotionControlType::torque;
|
||||
|
||||
// use monitoring with serial for motor init
|
||||
// comment out if not needed
|
||||
motor.useMonitoring(Serial);
|
||||
|
||||
// use monitoring with serial
|
||||
Serial.begin(115200);
|
||||
// comment out if not needed
|
||||
motor.useMonitoring(Serial);
|
||||
|
||||
// initialize motor
|
||||
motor.init();
|
||||
// align sensor and start FOC
|
||||
motor.initFOC();
|
||||
|
||||
// add target command T
|
||||
command.add('T', doTarget, "target voltage");
|
||||
|
||||
Serial.println(F("Motor ready."));
|
||||
Serial.println(F("Set the target voltage using serial terminal:"));
|
||||
_delay(1000);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
|
||||
// main FOC algorithm function
|
||||
// the faster you run this function the better
|
||||
// Arduino UNO loop ~1kHz
|
||||
// Bluepill loop ~10kHz
|
||||
motor.loopFOC();
|
||||
|
||||
// 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
|
||||
motor.move(target_voltage);
|
||||
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1,134 @@
|
||||
/*
|
||||
Odrive robotics' hardware is one of the best BLDC motor foc supporting hardware out there.
|
||||
|
||||
This is an example code that can be directly uploaded to the Odrive using the SWD programmer.
|
||||
This code uses an encoder with 500 cpr and a BLDC motor with 7 pole pairs connected to the M0 interface of the Odrive.
|
||||
|
||||
This is a short template code and the idea is that you are able to adapt to your needs not to be a complete solution. :D
|
||||
*/
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
// Odrive M0 motor pinout
|
||||
#define M0_INH_A PA8
|
||||
#define M0_INH_B PA9
|
||||
#define M0_INH_C PA10
|
||||
#define M0_INL_A PB13
|
||||
#define M0_INL_B PB14
|
||||
#define M0_INL_C PB15
|
||||
// M0 currnets
|
||||
#define M0_IB PC0
|
||||
#define M0_IC PC1
|
||||
// Odrive M0 encoder pinout
|
||||
#define M0_ENC_A PB4
|
||||
#define M0_ENC_B PB5
|
||||
#define M0_ENC_Z PC9
|
||||
|
||||
|
||||
// Odrive M1 motor pinout
|
||||
#define M1_INH_A PC6
|
||||
#define M1_INH_B PC7
|
||||
#define M1_INH_C PC8
|
||||
#define M1_INL_A PA7
|
||||
#define M1_INL_B PB0
|
||||
#define M1_INL_C PB1
|
||||
// M0 currnets
|
||||
#define M1_IB PC2
|
||||
#define M1_IC PC3
|
||||
// Odrive M1 encoder pinout
|
||||
#define M1_ENC_A PB6
|
||||
#define M1_ENC_B PB7
|
||||
#define M1_ENC_Z PC15
|
||||
|
||||
// M1 & M2 common enable pin
|
||||
#define EN_GATE PB12
|
||||
|
||||
// SPI pinout
|
||||
#define SPI3_SCL PC10
|
||||
#define SPI3_MISO PC11
|
||||
#define SPI3_MOSO PC12
|
||||
|
||||
// Motor instance
|
||||
BLDCMotor motor = BLDCMotor(7);
|
||||
BLDCDriver6PWM driver = BLDCDriver6PWM(M0_INH_A,M0_INL_A, M0_INH_B,M0_INL_B, M0_INH_C,M0_INL_C, EN_GATE);
|
||||
|
||||
// instantiate the commander
|
||||
Commander command = Commander(Serial);
|
||||
void doMotor(char* cmd) { command.motor(&motor, cmd); }
|
||||
|
||||
// low side current sensing define
|
||||
// 0.0005 Ohm resistor
|
||||
// gain of 10x
|
||||
// current sensing on B and C phases, phase A not connected
|
||||
LowsideCurrentSense current_sense = LowsideCurrentSense(0.0005f, 10.0f, _NC, M0_IB, M0_IC);
|
||||
|
||||
Encoder encoder = Encoder(M0_ENC_A, M0_ENC_B, 500,M0_ENC_Z);
|
||||
// Interrupt routine intialisation
|
||||
// channel A and B callbacks
|
||||
void doA(){encoder.handleA();}
|
||||
void doB(){encoder.handleB();}
|
||||
void doI(){encoder.handleIndex();}
|
||||
|
||||
void setup(){
|
||||
|
||||
// pwm frequency to be used [Hz]
|
||||
driver.pwm_frequency = 20000;
|
||||
// power supply voltage [V]
|
||||
driver.voltage_power_supply = 20;
|
||||
// Max DC voltage allowed - default voltage_power_supply
|
||||
driver.voltage_limit = 20;
|
||||
// driver init
|
||||
driver.init();
|
||||
// link the motor and the driver
|
||||
motor.linkDriver(&driver);
|
||||
|
||||
// initialize encoder sensor hardware
|
||||
encoder.init();
|
||||
encoder.enableInterrupts(doA, doB, doI);
|
||||
// link the motor to the sensor
|
||||
motor.linkSensor(&encoder);
|
||||
|
||||
// control loop type and torque mode
|
||||
motor.torque_controller = TorqueControlType::voltage;
|
||||
motor.controller = MotionControlType::torque;
|
||||
|
||||
// max voltage allowed for motion control
|
||||
motor.voltage_limit = 8.0;
|
||||
// alignment voltage limit
|
||||
motor.voltage_sensor_align = 0.5;
|
||||
|
||||
|
||||
Serial.begin(115200);
|
||||
// comment out if not needed
|
||||
motor.useMonitoring(Serial);
|
||||
motor.monitor_variables = _MON_CURR_Q | _MON_CURR_D;
|
||||
motor.monitor_downsample = 1000;
|
||||
|
||||
// add target command T
|
||||
command.add('M', doMotor, "motor M0");
|
||||
|
||||
// initialise motor
|
||||
motor.init();
|
||||
|
||||
// link the driver
|
||||
current_sense.linkDriver(&driver);
|
||||
// init the current sense
|
||||
current_sense.init();
|
||||
current_sense.skip_align = true;
|
||||
motor.linkCurrentSense(¤t_sense);
|
||||
|
||||
// init FOC
|
||||
motor.initFOC();
|
||||
delay(1000);
|
||||
}
|
||||
|
||||
void loop(){
|
||||
|
||||
// foc loop
|
||||
motor.loopFOC();
|
||||
// motion control
|
||||
motor.move();
|
||||
// monitoring
|
||||
motor.monitor();
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1,132 @@
|
||||
/*
|
||||
Odrive robotics' hardware is one of the best BLDC motor foc supporting hardware out there.
|
||||
|
||||
This is an example code that can be directly uploaded to the Odrive using the SWD programmer.
|
||||
This code uses an magnetic spi sensor AS5047 and a BLDC motor with 11 pole pairs connected to the M0 interface of the Odrive.
|
||||
|
||||
This is a short template code and the idea is that you are able to adapt to your needs not to be a complete solution. :D
|
||||
*/
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
// Odrive M0 motor pinout
|
||||
#define M0_INH_A PA8
|
||||
#define M0_INH_B PA9
|
||||
#define M0_INH_C PA10
|
||||
#define M0_INL_A PB13
|
||||
#define M0_INL_B PB14
|
||||
#define M0_INL_C PB15
|
||||
// M0 currnets
|
||||
#define M0_IB PC0
|
||||
#define M0_IC PC1
|
||||
// Odrive M0 encoder pinout
|
||||
#define M0_ENC_A PB4
|
||||
#define M0_ENC_B PB5
|
||||
#define M0_ENC_Z PC9
|
||||
|
||||
|
||||
// Odrive M1 motor pinout
|
||||
#define M1_INH_A PC6
|
||||
#define M1_INH_B PC7
|
||||
#define M1_INH_C PC8
|
||||
#define M1_INL_A PA7
|
||||
#define M1_INL_B PB0
|
||||
#define M1_INL_C PB1
|
||||
// M0 currnets
|
||||
#define M1_IB PC2
|
||||
#define M1_IC PC3
|
||||
// Odrive M1 encoder pinout
|
||||
#define M1_ENC_A PB6
|
||||
#define M1_ENC_B PB7
|
||||
#define M1_ENC_Z PC15
|
||||
|
||||
// M1 & M2 common enable pin
|
||||
#define EN_GATE PB12
|
||||
|
||||
// SPI pinout
|
||||
#define SPI3_SCL PC10
|
||||
#define SPI3_MISO PC11
|
||||
#define SPI3_MOSO PC12
|
||||
|
||||
// Motor instance
|
||||
BLDCMotor motor = BLDCMotor(11);
|
||||
BLDCDriver6PWM driver = BLDCDriver6PWM(M0_INH_A,M0_INL_A, M0_INH_B,M0_INL_B, M0_INH_C,M0_INL_C, EN_GATE);
|
||||
|
||||
// instantiate the commander
|
||||
Commander command = Commander(Serial);
|
||||
void doMotor(char* cmd) { command.motor(&motor, cmd); }
|
||||
|
||||
// low side current sensing define
|
||||
// 0.0005 Ohm resistor
|
||||
// gain of 10x
|
||||
// current sensing on B and C phases, phase A not connected
|
||||
LowsideCurrentSense current_sense = LowsideCurrentSense(0.0005f, 10.0f, _NC, M0_IB, M0_IC);
|
||||
|
||||
// MagneticSensorSPI(int cs, float _cpr, int _angle_register)
|
||||
// config - SPI config
|
||||
// cs - SPI chip select pin
|
||||
MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, M0_ENC_A);
|
||||
SPIClass SPI_3(SPI3_MOSO, SPI3_MISO, SPI3_SCL);
|
||||
|
||||
void setup(){
|
||||
|
||||
// pwm frequency to be used [Hz]
|
||||
driver.pwm_frequency = 20000;
|
||||
// power supply voltage [V]
|
||||
driver.voltage_power_supply = 20;
|
||||
// Max DC voltage allowed - default voltage_power_supply
|
||||
driver.voltage_limit = 20;
|
||||
// driver init
|
||||
driver.init();
|
||||
// link the motor and the driver
|
||||
motor.linkDriver(&driver);
|
||||
|
||||
// initialise magnetic sensor hardware
|
||||
sensor.init(&SPI_3);
|
||||
// link the motor to the sensor
|
||||
motor.linkSensor(&sensor);
|
||||
|
||||
// control loop type and torque mode
|
||||
motor.torque_controller = TorqueControlType::voltage;
|
||||
motor.controller = MotionControlType::torque;
|
||||
|
||||
// max voltage allowed for motion control
|
||||
motor.voltage_limit = 8.0;
|
||||
// alignment voltage limit
|
||||
motor.voltage_sensor_align = 0.5;
|
||||
|
||||
|
||||
Serial.begin(115200);
|
||||
// comment out if not needed
|
||||
motor.useMonitoring(Serial);
|
||||
motor.monitor_variables = _MON_CURR_Q | _MON_CURR_D;
|
||||
motor.monitor_downsample = 1000;
|
||||
|
||||
// add target command T
|
||||
command.add('M', doMotor, "motor M0");
|
||||
|
||||
// initialise motor
|
||||
motor.init();
|
||||
|
||||
// link the driver
|
||||
current_sense.linkDriver(&driver);
|
||||
// init the current sense
|
||||
current_sense.init();
|
||||
current_sense.skip_align = true;
|
||||
motor.linkCurrentSense(¤t_sense);
|
||||
|
||||
// init FOC
|
||||
motor.initFOC();
|
||||
delay(1000);
|
||||
}
|
||||
|
||||
void loop(){
|
||||
|
||||
// foc loop
|
||||
motor.loopFOC();
|
||||
// motion control
|
||||
motor.move();
|
||||
// monitoring
|
||||
motor.monitor();
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1,62 @@
|
||||
|
||||
# SAMD Support
|
||||
|
||||
SimpleFOC supports many SAMD21 MCUs, really any SAMD21 supported by Arduino core should work.
|
||||
|
||||
## Pin assignments
|
||||
|
||||
The SAMD chips have some very powerful PWM features, but do not have flexible pin assignments.
|
||||
|
||||
You should be able to use *most* (but not all!), pin combinations for attaching your motor's PWM pins. Please ignore the board descriptions and pinout diagrammes regarding PWM-pins on SAMD boards. They are pretty much all incorrect to varying degrees of awfulness.
|
||||
|
||||
On SAMD we use TCC and TC timer peripherals (built into the SAMD chip) to control the PWM. Depending on the chip there are various timer units, whose PWM outputs are attached to various different pins, and it is all very complicated. Luckily SimpleFOC sets it all up automatically *if* there is a compatible configuration for those pins.
|
||||
|
||||
Not all timers are created equal. The TCC timers are pretty awesome for PWM motor control, while the TC timers are just ok for the job. So to get best performance, you want to use just TCC timer pins if you can.
|
||||
|
||||
By enabling
|
||||
|
||||
```
|
||||
#define SIMPLEFOC_SAMD_DEBUG
|
||||
```
|
||||
|
||||
in drivers/hardware_specific/samd_mcu.cpp<br>
|
||||
you will see a table of pin assignments printed on the serial console, as well as the timers SimpleFOC was able to find and configure on the pins you specified. You can use this to optimize your choice of pins if you want.
|
||||
|
||||
You can configure up to 12 pins for PWM motor control, i.e. 6x 2-PWM motors, 4x 3-PWM motors, 3x 4-PWM motors or 2x 6-PWM motors.
|
||||
|
||||
## PWM control modes
|
||||
|
||||
All modes (3-PWM, 6-PWM, Stepper 2-PWM and Stepper 4-PWM) are supported.
|
||||
|
||||
For 2-, 3- amd 4- PWM, any valid pin-combinations can be used. If you stick to TCC timers rather than using TC timers, then you'll get getter PWM waveforms. If you use pins which are all on the same TCC unit, you'll get the best result, with the PWM signals all perfectly aligned as well.
|
||||
|
||||
For 6-PWM, the situation is much more complicated:<br>
|
||||
TC timers cannot be used for 6-PWM, only TCC timers.
|
||||
|
||||
For Hardware Dead-Time insertion, you must use H and L pins for one phase from the same TCC unit, and on the same channel, but using complementary WOs (Waveform Outputs, i.e. PWM output pins). Check the table to find pins on the same channel (like TCC0-0) but complementary WOs (like TCC0-0[0] and TCC0-0[4] or TCC1-0[0] and TCC1-0[2]).
|
||||
|
||||
For Software Dead-Time insertion, you must use the same TCC and different channels for the H and L pins of the same phase.
|
||||
|
||||
Note: in all of the above note that you *cannot* set the timers or WOs used - they are fixed, and determined by the pins you selected. SimpleFOC will find the best combination of timers given the pins, trying to use TCC timers before TC, and trying to keep things on the same timers as much as possible. If you configure multiple motors, it will take into account the pins already assigned to other motors.
|
||||
So it is matter of choosing the right pins, nothing else.
|
||||
|
||||
Note also: Unfortunately you can't set the PWM frequency. It is currently fixed at 24KHz. This is a tradeoff between limiting PWM resolution vs
|
||||
increasing frequency, and also due to keeping the pin assignemts flexible, which would not be possible if we ran the timers at different rates.
|
||||
|
||||
## Status
|
||||
|
||||
Currently, SAMD21 is supported, and SAMD51 is unsupported. SAMD51 support is in progress.
|
||||
|
||||
Boards tested:
|
||||
|
||||
* Arduino Nano 33 IoT
|
||||
* Arduino MKR1000
|
||||
* Arduino MKR1010 Wifi
|
||||
* Seeduino XIAO
|
||||
* Feather M0 Basic
|
||||
|
||||
Environments tested:
|
||||
|
||||
* Arduino IDE
|
||||
* Arduino Pro IDE
|
||||
* Sloeber
|
||||
@@ -0,0 +1,64 @@
|
||||
|
||||
// show the infos for SAMD pin assignment on serial console
|
||||
// set this #define SIMPLEFOC_SAMD_DEBUG in drivers/hardware_specific/samd21_mcu.h
|
||||
|
||||
|
||||
#include "Arduino.h"
|
||||
#include <Wire.h>
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
// this is for an AS5048B absolute magnetic encoder on I2C address 0x41
|
||||
MagneticSensorI2C sensor = MagneticSensorI2C(0x41, 14, 0xFE, 8);
|
||||
|
||||
// small BLDC gimbal motor, 7 pole-pairs
|
||||
BLDCMotor motor = BLDCMotor(7);
|
||||
// 3-PWM driving on pins 6, 5 and 8 - these are all on the same timer unit (TCC0), but different channels
|
||||
BLDCDriver3PWM driver = BLDCDriver3PWM(6,5,8);
|
||||
|
||||
// velocity set point variable
|
||||
float target_velocity = 2.0f;
|
||||
// instantiate the commander
|
||||
Commander command = Commander(SerialUSB);
|
||||
void doTarget(char* cmd) { command.scalar(&target_velocity, cmd); }
|
||||
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
delay(1000);
|
||||
Serial.println("Initializing...");
|
||||
|
||||
sensor.init();
|
||||
Wire.setClock(400000);
|
||||
motor.linkSensor(&sensor);
|
||||
driver.voltage_power_supply = 9;
|
||||
driver.init();
|
||||
motor.linkDriver(&driver);
|
||||
motor.controller = MotionControlType::velocity;
|
||||
motor.PID_velocity.P = 0.2f;
|
||||
motor.PID_velocity.I = 20;
|
||||
motor.PID_velocity.D = 0.001f;
|
||||
motor.PID_velocity.output_ramp = 1000;
|
||||
motor.LPF_velocity.Tf = 0.01f;
|
||||
motor.voltage_limit = 9;
|
||||
//motor.P_angle.P = 20;
|
||||
motor.init();
|
||||
motor.initFOC();
|
||||
|
||||
// add target command T
|
||||
command.add('T', doTarget, "target velocity");
|
||||
|
||||
Serial.println(F("Motor ready."));
|
||||
Serial.println(F("Set the target velocity using serial terminal:"));
|
||||
delay(100);
|
||||
}
|
||||
|
||||
|
||||
|
||||
void loop() {
|
||||
// Serial.print("Sensor: ");
|
||||
// Serial.println(sensor.getAngle());
|
||||
motor.loopFOC();
|
||||
motor.move(target_velocity);
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1,102 @@
|
||||
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
// BLDC motor & driver instance
|
||||
BLDCMotor motor = BLDCMotor(7);
|
||||
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8, 4, 7);
|
||||
|
||||
// encoder instance
|
||||
Encoder encoder = Encoder(10, 11, 500);
|
||||
// channel A and B callbacks
|
||||
void doA(){encoder.handleA();}
|
||||
void doB(){encoder.handleB();}
|
||||
|
||||
// inline current sensor instance
|
||||
InlineCurrentSense current_sense = InlineCurrentSense(0.001f, 50.0f, A0, A1);
|
||||
|
||||
// commander communication instance
|
||||
Commander command = Commander(Serial);
|
||||
// void doMotor(char* cmd){ command.motor(&motor, cmd); }
|
||||
void doTarget(char* cmd){ command.scalar(&motor.target, cmd); }
|
||||
|
||||
void setup() {
|
||||
|
||||
// initialize encoder sensor hardware
|
||||
encoder.init();
|
||||
encoder.enableInterrupts(doA, doB);
|
||||
// link the motor to the sensor
|
||||
motor.linkSensor(&encoder);
|
||||
|
||||
// driver config
|
||||
// power supply voltage [V]
|
||||
driver.voltage_power_supply = 20;
|
||||
driver.init();
|
||||
// link driver
|
||||
motor.linkDriver(&driver);
|
||||
// link current sense and the driver
|
||||
current_sense.linkDriver(&driver);
|
||||
|
||||
motor.voltage_sensor_align = 1;
|
||||
// set control loop type to be used
|
||||
motor.torque_controller = TorqueControlType::foc_current;
|
||||
motor.controller = MotionControlType::torque;
|
||||
|
||||
// contoller configuration based on the controll type
|
||||
motor.PID_velocity.P = 0.05f;
|
||||
motor.PID_velocity.I = 1;
|
||||
motor.PID_velocity.D = 0;
|
||||
// default voltage_power_supply
|
||||
motor.voltage_limit = 12;
|
||||
|
||||
// velocity low pass filtering time constant
|
||||
motor.LPF_velocity.Tf = 0.01f;
|
||||
|
||||
// angle loop controller
|
||||
motor.P_angle.P = 20;
|
||||
// angle loop velocity limit
|
||||
motor.velocity_limit = 20;
|
||||
|
||||
// use monitoring with serial for motor init
|
||||
// monitoring port
|
||||
Serial.begin(115200);
|
||||
// comment out if not needed
|
||||
motor.useMonitoring(Serial);
|
||||
motor.monitor_downsample = 0; // disable intially
|
||||
motor.monitor_variables = _MON_TARGET | _MON_VEL | _MON_ANGLE; // monitor target velocity and angle
|
||||
|
||||
// current sense init and linking
|
||||
current_sense.init();
|
||||
motor.linkCurrentSense(¤t_sense);
|
||||
|
||||
// initialise motor
|
||||
motor.init();
|
||||
// align encoder and start FOC
|
||||
motor.initFOC();
|
||||
|
||||
// set the inital target value
|
||||
motor.target = 0;
|
||||
|
||||
// subscribe motor to the commander
|
||||
// command.add('M', doMotor, "motor");
|
||||
command.add('T', doTarget, "target");
|
||||
|
||||
// Run user commands to configure and the motor (find the full command list in docs.simplefoc.com)
|
||||
Serial.println("Motor ready.");
|
||||
|
||||
_delay(1000);
|
||||
}
|
||||
|
||||
|
||||
void loop() {
|
||||
// iterative setting FOC phase voltage
|
||||
motor.loopFOC();
|
||||
|
||||
// iterative function setting the outter loop target
|
||||
motor.move();
|
||||
|
||||
// motor monitoring
|
||||
motor.monitor();
|
||||
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1,125 @@
|
||||
/**
|
||||
*
|
||||
* SimpleFOCMini motor control example
|
||||
*
|
||||
* For Arduino UNO, the most convenient way to use the board is to stack it to the pins:
|
||||
* - 12 - GND
|
||||
* - 11 - IN1
|
||||
* - 10 - IN2
|
||||
* - 9 - IN3
|
||||
* - 8 - EN
|
||||
*
|
||||
* For other boards with UNO headers but more PWM channles such as esp32, nucleo-64, samd51 metro etc, the best way to most convenient pinout is:
|
||||
* - GND - GND
|
||||
* - 13 - IN1
|
||||
* - 12 - IN2
|
||||
* - 11 - IN3
|
||||
* - 9 - EN
|
||||
*
|
||||
* For the boards without arduino uno headers, the choice of pinout is a lot less constrained.
|
||||
*
|
||||
*/
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
|
||||
// BLDC motor & driver instance
|
||||
BLDCMotor motor = BLDCMotor(11);
|
||||
BLDCDriver3PWM driver = BLDCDriver3PWM(11, 10, 9, 8);
|
||||
|
||||
// encoder instance
|
||||
Encoder encoder = Encoder(2, 3, 500);
|
||||
// Interrupt routine intialisation
|
||||
// channel A and B callbacks
|
||||
void doA(){encoder.handleA();}
|
||||
void doB(){encoder.handleB();}
|
||||
|
||||
// instantiate the commander
|
||||
Commander command = Commander(Serial);
|
||||
void doMotor(char* cmd) { command.motor(&motor, cmd); }
|
||||
|
||||
void setup() {
|
||||
// if SimpleFOCMini is stacked in arduino headers
|
||||
// on pins 12,11,10,9,8
|
||||
// pin 12 is used as ground
|
||||
pinMode(12,OUTPUT);
|
||||
pinMode(12,LOW);
|
||||
|
||||
// initialize encoder sensor hardware
|
||||
encoder.init();
|
||||
encoder.enableInterrupts(doA, doB);
|
||||
// link the motor to the sensor
|
||||
motor.linkSensor(&encoder);
|
||||
|
||||
// driver config
|
||||
// power supply voltage [V]
|
||||
driver.voltage_power_supply = 12;
|
||||
driver.init();
|
||||
// link the motor and the driver
|
||||
motor.linkDriver(&driver);
|
||||
|
||||
// aligning voltage [V]
|
||||
motor.voltage_sensor_align = 3;
|
||||
|
||||
// set motion control loop to be used
|
||||
motor.controller = MotionControlType::angle;
|
||||
|
||||
// contoller configuration
|
||||
// default parameters in defaults.h
|
||||
|
||||
// velocity PI controller parameters
|
||||
motor.PID_velocity.P = 0.2f;
|
||||
motor.PID_velocity.I = 20;
|
||||
motor.PID_velocity.D = 0;
|
||||
// default voltage_power_supply
|
||||
motor.voltage_limit = 6;
|
||||
// jerk control using voltage voltage ramp
|
||||
// default value is 300 volts per sec ~ 0.3V per millisecond
|
||||
motor.PID_velocity.output_ramp = 1000;
|
||||
|
||||
// velocity low pass filtering time constant
|
||||
motor.LPF_velocity.Tf = 0.01f;
|
||||
|
||||
// angle P controller
|
||||
motor.P_angle.P = 20;
|
||||
// maximal velocity of the position control
|
||||
motor.velocity_limit = 4;
|
||||
|
||||
|
||||
// use monitoring with serial
|
||||
Serial.begin(115200);
|
||||
// comment out if not needed
|
||||
motor.useMonitoring(Serial);
|
||||
|
||||
// initialize motor
|
||||
motor.init();
|
||||
// align encoder and start FOC
|
||||
motor.initFOC();
|
||||
|
||||
// add target command M
|
||||
command.add('M', doMotor, "motor");
|
||||
|
||||
Serial.println(F("Motor ready."));
|
||||
Serial.println(F("Set the target angle using serial terminal:"));
|
||||
_delay(1000);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// main FOC algorithm function
|
||||
// the faster you run this function the better
|
||||
// Arduino UNO loop ~1kHz
|
||||
// Bluepill loop ~10kHz
|
||||
motor.loopFOC();
|
||||
|
||||
// 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
|
||||
motor.move();
|
||||
|
||||
// function intended to be used with serial plotter to monitor motor variables
|
||||
// significantly slowing the execution down!!!!
|
||||
// motor.monitor();
|
||||
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1,118 @@
|
||||
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
// BLDC motor & driver instance
|
||||
BLDCMotor motor1 = BLDCMotor(11);
|
||||
BLDCDriver3PWM driver1 = BLDCDriver3PWM(9, 5, 6, 8);
|
||||
|
||||
// BLDC motor & driver instance
|
||||
BLDCMotor motor2 = BLDCMotor(11);
|
||||
BLDCDriver3PWM driver2 = BLDCDriver3PWM(3, 10, 11, 7);
|
||||
|
||||
// encoder instance
|
||||
Encoder encoder1 = Encoder(2, A3, 500);
|
||||
// channel A and B callbacks
|
||||
void doA1(){encoder1.handleA();}
|
||||
void doB1(){encoder1.handleB();}
|
||||
|
||||
// encoder instance
|
||||
Encoder encoder2 = Encoder(A1, A2, 500);
|
||||
// channel A and B callbacks
|
||||
void doA2(){encoder2.handleA();}
|
||||
void doB2(){encoder2.handleB();}
|
||||
|
||||
// commander communication instance
|
||||
Commander command = Commander(Serial);
|
||||
void doMotor1(char* cmd){ command.motor(&motor1, cmd); }
|
||||
void doMotor2(char* cmd){ command.motor(&motor2, cmd); }
|
||||
|
||||
void setup() {
|
||||
|
||||
// initialize encoder sensor hardware
|
||||
encoder1.init();
|
||||
encoder1.enableInterrupts(doA1, doB1);
|
||||
// initialize encoder sensor hardware
|
||||
encoder2.init();
|
||||
encoder2.enableInterrupts(doA2, doB2);
|
||||
// link the motor to the sensor
|
||||
motor1.linkSensor(&encoder1);
|
||||
motor2.linkSensor(&encoder2);
|
||||
|
||||
|
||||
// driver config
|
||||
// power supply voltage [V]
|
||||
driver1.voltage_power_supply = 12;
|
||||
driver1.init();
|
||||
// link driver
|
||||
motor1.linkDriver(&driver1);
|
||||
// power supply voltage [V]
|
||||
driver2.voltage_power_supply = 12;
|
||||
driver2.init();
|
||||
// link driver
|
||||
motor2.linkDriver(&driver2);
|
||||
|
||||
// set control loop type to be used
|
||||
motor1.controller = MotionControlType::torque;
|
||||
motor2.controller = MotionControlType::torque;
|
||||
|
||||
// contoller configuration based on the controll type
|
||||
motor1.PID_velocity.P = 0.05f;
|
||||
motor1.PID_velocity.I = 1;
|
||||
motor1.PID_velocity.D = 0;
|
||||
// default voltage_power_supply
|
||||
motor1.voltage_limit = 12;
|
||||
// contoller configuration based on the controll type
|
||||
motor2.PID_velocity.P = 0.05f;
|
||||
motor2.PID_velocity.I = 1;
|
||||
motor2.PID_velocity.D = 0;
|
||||
// default voltage_power_supply
|
||||
motor2.voltage_limit = 12;
|
||||
|
||||
// angle loop velocity limit
|
||||
motor1.velocity_limit = 20;
|
||||
motor2.velocity_limit = 20;
|
||||
|
||||
// use monitoring with serial for motor init
|
||||
// monitoring port
|
||||
Serial.begin(115200);
|
||||
// comment out if not needed
|
||||
motor1.useMonitoring(Serial);
|
||||
motor2.useMonitoring(Serial);
|
||||
|
||||
// initialise motor
|
||||
motor1.init();
|
||||
// align encoder and start FOC
|
||||
motor1.initFOC();
|
||||
|
||||
// initialise motor
|
||||
motor2.init();
|
||||
// align encoder and start FOC
|
||||
motor2.initFOC();
|
||||
|
||||
// set the inital target value
|
||||
motor1.target = 2;
|
||||
motor2.target = 2;
|
||||
|
||||
// subscribe motor to the commander
|
||||
command.add('A', doMotor1, "motor 1");
|
||||
command.add('B', doMotor2, "motor 2");
|
||||
|
||||
// Run user commands to configure and the motor (find the full command list in docs.simplefoc.com)
|
||||
Serial.println(F("Double motor sketch ready."));
|
||||
|
||||
_delay(1000);
|
||||
}
|
||||
|
||||
|
||||
void loop() {
|
||||
// iterative setting FOC phase voltage
|
||||
motor1.loopFOC();
|
||||
motor2.loopFOC();
|
||||
|
||||
// iterative function setting the outter loop target
|
||||
motor1.move();
|
||||
motor2.move();
|
||||
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1,89 @@
|
||||
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
// BLDC motor & driver instance
|
||||
BLDCMotor motor = BLDCMotor(11);
|
||||
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
|
||||
|
||||
// encoder instance
|
||||
Encoder encoder = Encoder(2, 3, 500);
|
||||
// channel A and B callbacks
|
||||
void doA(){encoder.handleA();}
|
||||
void doB(){encoder.handleB();}
|
||||
|
||||
// commander communication instance
|
||||
Commander command = Commander(Serial);
|
||||
void doMotor(char* cmd){ command.motor(&motor, cmd); }
|
||||
|
||||
void setup() {
|
||||
|
||||
// initialize encoder sensor hardware
|
||||
encoder.init();
|
||||
encoder.enableInterrupts(doA, doB);
|
||||
// link the motor to the sensor
|
||||
motor.linkSensor(&encoder);
|
||||
|
||||
// driver config
|
||||
// power supply voltage [V]
|
||||
driver.voltage_power_supply = 12;
|
||||
driver.init();
|
||||
// link driver
|
||||
motor.linkDriver(&driver);
|
||||
|
||||
// set control loop type to be used
|
||||
motor.controller = MotionControlType::torque;
|
||||
|
||||
// contoller configuration based on the controll type
|
||||
motor.PID_velocity.P = 0.05f;
|
||||
motor.PID_velocity.I = 1;
|
||||
motor.PID_velocity.D = 0;
|
||||
// default voltage_power_supply
|
||||
motor.voltage_limit = 12;
|
||||
|
||||
// velocity low pass filtering time constant
|
||||
motor.LPF_velocity.Tf = 0.01f;
|
||||
|
||||
// angle loop controller
|
||||
motor.P_angle.P = 20;
|
||||
// angle loop velocity limit
|
||||
motor.velocity_limit = 20;
|
||||
|
||||
// use monitoring with serial for motor init
|
||||
// monitoring port
|
||||
Serial.begin(115200);
|
||||
// comment out if not needed
|
||||
motor.useMonitoring(Serial);
|
||||
motor.monitor_downsample = 0; // disable intially
|
||||
motor.monitor_variables = _MON_TARGET | _MON_VEL | _MON_ANGLE; // monitor target velocity and angle
|
||||
|
||||
// initialise motor
|
||||
motor.init();
|
||||
// align encoder and start FOC
|
||||
motor.initFOC();
|
||||
|
||||
// set the inital target value
|
||||
motor.target = 2;
|
||||
|
||||
// subscribe motor to the commander
|
||||
command.add('M', doMotor, "motor");
|
||||
|
||||
// Run user commands to configure and the motor (find the full command list in docs.simplefoc.com)
|
||||
Serial.println(F("Motor commands sketch | Initial motion control > torque/voltage : target 2V."));
|
||||
|
||||
_delay(1000);
|
||||
}
|
||||
|
||||
|
||||
void loop() {
|
||||
// iterative setting FOC phase voltage
|
||||
motor.loopFOC();
|
||||
|
||||
// iterative function setting the outter loop target
|
||||
motor.move();
|
||||
|
||||
// motor monitoring
|
||||
motor.monitor();
|
||||
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1,144 @@
|
||||
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
// BLDC motor & driver instance
|
||||
BLDCMotor motor1 = BLDCMotor(11);
|
||||
BLDCDriver3PWM driver1 = BLDCDriver3PWM(5, 10, 6, 8);
|
||||
|
||||
// BLDC motor & driver instance
|
||||
BLDCMotor motor2 = BLDCMotor(11);
|
||||
BLDCDriver3PWM driver2 = BLDCDriver3PWM(3, 9, 11, 7);
|
||||
|
||||
// encoder instance
|
||||
Encoder encoder1 = Encoder(12, 2, 500);
|
||||
// channel A and B callbacks
|
||||
void doA1(){encoder1.handleA();}
|
||||
void doB1(){encoder1.handleB();}
|
||||
|
||||
// encoder instance
|
||||
Encoder encoder2 = Encoder(A5, A4, 500);
|
||||
// channel A and B callbacks
|
||||
void doA2(){encoder2.handleA();}
|
||||
void doB2(){encoder2.handleB();}
|
||||
|
||||
|
||||
// inline current sensor instance
|
||||
// check if your board has R010 (0.01 ohm resistor) or R006 (0.006 mOhm resistor)
|
||||
InlineCurrentSense current_sense1 = InlineCurrentSense(0.01f, 50.0f, A0, A2);
|
||||
|
||||
// inline current sensor instance
|
||||
// check if your board has R010 (0.01 ohm resistor) or R006 (0.006 mOhm resistor)
|
||||
InlineCurrentSense current_sense2 = InlineCurrentSense(0.01f, 50.0f, A1, A3);
|
||||
|
||||
// commander communication instance
|
||||
Commander command = Commander(Serial);
|
||||
// void doMotor1(char* cmd){ command.motor(&motor1, cmd); }
|
||||
// void doMotor2(char* cmd){ command.motor(&motor2, cmd); }
|
||||
void doTarget1(char* cmd){ command.scalar(&motor1.target, cmd); }
|
||||
void doTarget2(char* cmd){ command.scalar(&motor2.target, cmd); }
|
||||
|
||||
void setup() {
|
||||
|
||||
// initialize encoder sensor hardware
|
||||
encoder1.init();
|
||||
encoder1.enableInterrupts(doA1, doB1);
|
||||
// initialize encoder sensor hardware
|
||||
encoder2.init();
|
||||
encoder2.enableInterrupts(doA2, doB2);
|
||||
// link the motor to the sensor
|
||||
motor1.linkSensor(&encoder1);
|
||||
motor2.linkSensor(&encoder2);
|
||||
|
||||
|
||||
// driver config
|
||||
// power supply voltage [V]
|
||||
driver1.voltage_power_supply = 12;
|
||||
driver1.init();
|
||||
// link driver
|
||||
motor1.linkDriver(&driver1);
|
||||
// link current sense and the driver
|
||||
current_sense1.linkDriver(&driver1);
|
||||
|
||||
// power supply voltage [V]
|
||||
driver2.voltage_power_supply = 12;
|
||||
driver2.init();
|
||||
// link driver
|
||||
motor2.linkDriver(&driver2);
|
||||
// link current sense and the driver
|
||||
current_sense2.linkDriver(&driver2);
|
||||
|
||||
// set control loop type to be used
|
||||
motor1.controller = MotionControlType::torque;
|
||||
motor2.controller = MotionControlType::torque;
|
||||
|
||||
// contoller configuration based on the controll type
|
||||
motor1.PID_velocity.P = 0.05f;
|
||||
motor1.PID_velocity.I = 1;
|
||||
motor1.PID_velocity.D = 0;
|
||||
// default voltage_power_supply
|
||||
motor1.voltage_limit = 12;
|
||||
// contoller configuration based on the controll type
|
||||
motor2.PID_velocity.P = 0.05f;
|
||||
motor2.PID_velocity.I = 1;
|
||||
motor2.PID_velocity.D = 0;
|
||||
// default voltage_power_supply
|
||||
motor2.voltage_limit = 12;
|
||||
|
||||
// angle loop velocity limit
|
||||
motor1.velocity_limit = 20;
|
||||
motor2.velocity_limit = 20;
|
||||
|
||||
// use monitoring with serial for motor init
|
||||
// monitoring port
|
||||
Serial.begin(115200);
|
||||
// comment out if not needed
|
||||
motor1.useMonitoring(Serial);
|
||||
motor2.useMonitoring(Serial);
|
||||
|
||||
|
||||
// current sense init and linking
|
||||
current_sense1.init();
|
||||
motor1.linkCurrentSense(¤t_sense1);
|
||||
// current sense init and linking
|
||||
current_sense2.init();
|
||||
motor2.linkCurrentSense(¤t_sense2);
|
||||
|
||||
// initialise motor
|
||||
motor1.init();
|
||||
// align encoder and start FOC
|
||||
motor1.initFOC();
|
||||
|
||||
// initialise motor
|
||||
motor2.init();
|
||||
// align encoder and start FOC
|
||||
motor2.initFOC();
|
||||
|
||||
// set the inital target value
|
||||
motor1.target = 2;
|
||||
motor2.target = 2;
|
||||
|
||||
// subscribe motor to the commander
|
||||
// command.add('A', doMotor1, "motor 1");
|
||||
// command.add('B', doMotor2, "motor 2");
|
||||
command.add('A', doTarget1, "target 1");
|
||||
command.add('B', doTarget2, "target 2");
|
||||
|
||||
// Run user commands to configure and the motor (find the full command list in docs.simplefoc.com)
|
||||
Serial.println("Motors ready.");
|
||||
|
||||
_delay(1000);
|
||||
}
|
||||
|
||||
|
||||
void loop() {
|
||||
// iterative setting FOC phase voltage
|
||||
motor1.loopFOC();
|
||||
motor2.loopFOC();
|
||||
|
||||
// iterative function setting the outter loop target
|
||||
motor1.move();
|
||||
motor2.move();
|
||||
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1,101 @@
|
||||
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
// BLDC motor & driver instance
|
||||
BLDCMotor motor = BLDCMotor(11);
|
||||
BLDCDriver3PWM driver = BLDCDriver3PWM(5, 10, 6, 8);
|
||||
|
||||
// encoder instance
|
||||
Encoder encoder = Encoder(2, 3, 500);
|
||||
// channel A and B callbacks
|
||||
void doA(){encoder.handleA();}
|
||||
void doB(){encoder.handleB();}
|
||||
|
||||
// inline current sensor instance
|
||||
// check if your board has R010 (0.01 ohm resistor) or R006 (0.006 mOhm resistor)
|
||||
InlineCurrentSense current_sense = InlineCurrentSense(0.01f, 50.0f, A0, A2);
|
||||
|
||||
// commander communication instance
|
||||
Commander command = Commander(Serial);
|
||||
void doMotion(char* cmd){ command.motion(&motor, cmd); }
|
||||
// void doMotor(char* cmd){ command.motor(&motor, cmd); }
|
||||
|
||||
void setup() {
|
||||
|
||||
// initialize encoder sensor hardware
|
||||
encoder.init();
|
||||
encoder.enableInterrupts(doA, doB);
|
||||
// link the motor to the sensor
|
||||
motor.linkSensor(&encoder);
|
||||
|
||||
// driver config
|
||||
// power supply voltage [V]
|
||||
driver.voltage_power_supply = 12;
|
||||
driver.init();
|
||||
// link driver
|
||||
motor.linkDriver(&driver);
|
||||
// link current sense and the driver
|
||||
current_sense.linkDriver(&driver);
|
||||
|
||||
// set control loop type to be used
|
||||
motor.controller = MotionControlType::torque;
|
||||
|
||||
// contoller configuration based on the controll type
|
||||
motor.PID_velocity.P = 0.05f;
|
||||
motor.PID_velocity.I = 1;
|
||||
motor.PID_velocity.D = 0;
|
||||
// default voltage_power_supply
|
||||
motor.voltage_limit = 12;
|
||||
|
||||
// velocity low pass filtering time constant
|
||||
motor.LPF_velocity.Tf = 0.01f;
|
||||
|
||||
// angle loop controller
|
||||
motor.P_angle.P = 20;
|
||||
// angle loop velocity limit
|
||||
motor.velocity_limit = 20;
|
||||
|
||||
// use monitoring with serial for motor init
|
||||
// monitoring port
|
||||
Serial.begin(115200);
|
||||
// comment out if not needed
|
||||
motor.useMonitoring(Serial);
|
||||
motor.monitor_downsample = 0; // disable intially
|
||||
motor.monitor_variables = _MON_TARGET | _MON_VEL | _MON_ANGLE; // monitor target velocity and angle
|
||||
|
||||
// current sense init and linking
|
||||
current_sense.init();
|
||||
motor.linkCurrentSense(¤t_sense);
|
||||
|
||||
// initialise motor
|
||||
motor.init();
|
||||
// align encoder and start FOC
|
||||
motor.initFOC();
|
||||
|
||||
// set the inital target value
|
||||
motor.target = 2;
|
||||
|
||||
// subscribe motor to the commander
|
||||
command.add('T', doMotion, "motion control");
|
||||
// command.add('M', doMotor, "motor");
|
||||
|
||||
// Run user commands to configure and the motor (find the full command list in docs.simplefoc.com)
|
||||
Serial.println("Motor ready.");
|
||||
|
||||
_delay(1000);
|
||||
}
|
||||
|
||||
|
||||
void loop() {
|
||||
// iterative setting FOC phase voltage
|
||||
motor.loopFOC();
|
||||
|
||||
// iterative function setting the outter loop target
|
||||
motor.move();
|
||||
|
||||
// motor monitoring
|
||||
motor.monitor();
|
||||
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1,101 @@
|
||||
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
// BLDC motor & driver instance
|
||||
BLDCMotor motor = BLDCMotor(11);
|
||||
BLDCDriver3PWM driver = BLDCDriver3PWM(6, 10, 5, 8);
|
||||
|
||||
// encoder instance
|
||||
Encoder encoder = Encoder(2, 3, 500);
|
||||
// channel A and B callbacks
|
||||
void doA(){encoder.handleA();}
|
||||
void doB(){encoder.handleB();}
|
||||
|
||||
// inline current sensor instance
|
||||
// ACS712-05B has the resolution of 0.185mV per Amp
|
||||
InlineCurrentSense current_sense = InlineCurrentSense(1.0f, 0.185f, A0, A2);
|
||||
|
||||
// commander communication instance
|
||||
Commander command = Commander(Serial);
|
||||
void doMotion(char* cmd){ command.motion(&motor, cmd); }
|
||||
// void doMotor(char* cmd){ command.motor(&motor, cmd); }
|
||||
|
||||
void setup() {
|
||||
|
||||
// initialize encoder sensor hardware
|
||||
encoder.init();
|
||||
encoder.enableInterrupts(doA, doB);
|
||||
// link the motor to the sensor
|
||||
motor.linkSensor(&encoder);
|
||||
|
||||
// driver config
|
||||
// power supply voltage [V]
|
||||
driver.voltage_power_supply = 12;
|
||||
driver.init();
|
||||
// link driver
|
||||
motor.linkDriver(&driver);
|
||||
// link current sense and the driver
|
||||
current_sense.linkDriver(&driver);
|
||||
|
||||
// set control loop type to be used
|
||||
motor.controller = MotionControlType::torque;
|
||||
|
||||
// controller configuration based on the control type
|
||||
motor.PID_velocity.P = 0.05f;
|
||||
motor.PID_velocity.I = 1;
|
||||
motor.PID_velocity.D = 0;
|
||||
// default voltage_power_supply
|
||||
motor.voltage_limit = 12;
|
||||
|
||||
// velocity low pass filtering time constant
|
||||
motor.LPF_velocity.Tf = 0.01f;
|
||||
|
||||
// angle loop controller
|
||||
motor.P_angle.P = 20;
|
||||
// angle loop velocity limit
|
||||
motor.velocity_limit = 20;
|
||||
|
||||
// use monitoring with serial for motor init
|
||||
// monitoring port
|
||||
Serial.begin(115200);
|
||||
// comment out if not needed
|
||||
motor.useMonitoring(Serial);
|
||||
motor.monitor_downsample = 0; // disable intially
|
||||
motor.monitor_variables = _MON_TARGET | _MON_VEL | _MON_ANGLE; // monitor target velocity and angle
|
||||
|
||||
// current sense init and linking
|
||||
current_sense.init();
|
||||
motor.linkCurrentSense(¤t_sense);
|
||||
|
||||
// initialise motor
|
||||
motor.init();
|
||||
// align encoder and start FOC
|
||||
motor.initFOC();
|
||||
|
||||
// set the inital target value
|
||||
motor.target = 2;
|
||||
|
||||
// subscribe motor to the commander
|
||||
command.add('T', doMotion, "motion control");
|
||||
// command.add('M', doMotor, "motor");
|
||||
|
||||
// Run user commands to configure and the motor (find the full command list in docs.simplefoc.com)
|
||||
Serial.println("Motor ready.");
|
||||
|
||||
_delay(1000);
|
||||
}
|
||||
|
||||
|
||||
void loop() {
|
||||
// iterative setting FOC phase voltage
|
||||
motor.loopFOC();
|
||||
|
||||
// iterative function setting the outter loop target
|
||||
motor.move();
|
||||
|
||||
// motor monitoring
|
||||
motor.monitor();
|
||||
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1,61 @@
|
||||
/**
|
||||
* Smart Stepper support with SimpleFOClibrary
|
||||
*/
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
// magnetic sensor instance - SPI
|
||||
MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, A2);
|
||||
|
||||
// Stepper motor & driver instance
|
||||
StepperMotor motor = StepperMotor(50);
|
||||
int in1[2] = {5, 6};
|
||||
int in2[2] = {A4, 7};
|
||||
StepperDriver2PWM driver = StepperDriver2PWM(4, in1, 9, in2);
|
||||
|
||||
// instantiate the commander
|
||||
Commander command = Commander(SerialUSB);
|
||||
void doMotor(char* cmd) { command.motor(&motor, cmd); }
|
||||
|
||||
void setup() {
|
||||
|
||||
// initialise magnetic sensor hardware
|
||||
sensor.init();
|
||||
// link the motor to the sensor
|
||||
motor.linkSensor(&sensor);
|
||||
|
||||
// power supply voltage
|
||||
driver.voltage_power_supply = 12;
|
||||
driver.init();
|
||||
motor.linkDriver(&driver);
|
||||
|
||||
// set motion control loop to be used
|
||||
motor.controller = MotionControlType::torque;
|
||||
|
||||
// use monitoring with SerialUSB
|
||||
SerialUSB.begin(115200);
|
||||
// comment out if not needed
|
||||
motor.useMonitoring(SerialUSB);
|
||||
|
||||
// initialize motor
|
||||
motor.init();
|
||||
// align sensor and start FOC
|
||||
motor.initFOC();
|
||||
|
||||
// add target command M
|
||||
command.add('M', doMotor, "my motor");
|
||||
|
||||
SerialUSB.println(F("Motor ready."));
|
||||
SerialUSB.println(F("Set the target voltage using Serial terminal:"));
|
||||
_delay(1000);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// main FOC algorithm function
|
||||
motor.loopFOC();
|
||||
|
||||
// Motion control function
|
||||
motor.move();
|
||||
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1,41 @@
|
||||
// 6pwm standalone example code for Teensy 3.x boards
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
|
||||
// BLDC driver instance
|
||||
// using FTM0 timer
|
||||
BLDCDriver6PWM driver = BLDCDriver6PWM(22,23, 9,10, 6,20, 8);
|
||||
// using FTM3 timer - available on Teensy3.5 and Teensy3.6
|
||||
// BLDCDriver6PWM driver = BLDCDriver6PWM(2,14, 7,8, 35,36, 8);
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
// Enable debugging
|
||||
// Driver init will show debugging output
|
||||
SimpleFOCDebug::enable(&Serial);
|
||||
|
||||
// pwm frequency to be used [Hz]
|
||||
driver.pwm_frequency = 30000;
|
||||
// dead zone percentage of the duty cycle - default 0.02 - 2%
|
||||
driver.dead_zone=0.02;
|
||||
// power supply voltage [V]
|
||||
driver.voltage_power_supply = 12;
|
||||
// Max DC voltage allowed - default voltage_power_supply
|
||||
driver.voltage_limit = 12;
|
||||
|
||||
// driver init
|
||||
driver.init();
|
||||
|
||||
// enable driver
|
||||
driver.enable();
|
||||
|
||||
_delay(1000);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// setting pwm
|
||||
// phase A: 3V
|
||||
// phase B: 6V
|
||||
// phase C: 5V
|
||||
driver.setPwm(3,6,5);
|
||||
}
|
||||
@@ -0,0 +1,65 @@
|
||||
// 6pwm openloop velocity example
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
|
||||
// BLDC motor & driver instance
|
||||
// BLDCMotor motor = BLDCMotor(pole pair number);
|
||||
BLDCMotor motor = BLDCMotor(11);
|
||||
// using FTM0 timer
|
||||
// BLDCDriver6PWM(pwmA_H, pwmA_L, pwmB_H,pwmB_L, pwmC_H, pwmC_L)
|
||||
BLDCDriver6PWM driver = BLDCDriver6PWM(22,23, 9,10, 6,20, 8);
|
||||
// using FTM3 timer - available on Teensy3.5 and Teensy3.6
|
||||
// BLDCDriver6PWM driver = BLDCDriver6PWM(2,14, 7,8, 35,36, 8);
|
||||
|
||||
// instantiate the commander
|
||||
Commander command = Commander(Serial);
|
||||
void doTarget(char* cmd) { command.scalar(&motor.target, cmd); }
|
||||
void doLimit(char* cmd) { command.scalar(&motor.voltage_limit, cmd); }
|
||||
|
||||
void setup() {
|
||||
|
||||
// driver config
|
||||
// power supply voltage [V]
|
||||
driver.voltage_power_supply = 12;
|
||||
// limit the maximal dc voltage the driver can set
|
||||
// as a protection measure for the low-resistance motors
|
||||
// this value is fixed on startup
|
||||
driver.voltage_limit = 6;
|
||||
driver.init();
|
||||
// link the motor and the driver
|
||||
motor.linkDriver(&driver);
|
||||
|
||||
// limiting motor movements
|
||||
// limit the voltage to be set to the motor
|
||||
// start very low for high resistance motors
|
||||
// currnet = resistance*voltage, so try to be well under 1Amp
|
||||
motor.voltage_limit = 3; // [V]
|
||||
|
||||
// open loop control config
|
||||
motor.controller = MotionControlType::velocity_openloop;
|
||||
|
||||
// init motor hardware
|
||||
motor.init();
|
||||
|
||||
//initial motor target
|
||||
motor.target=0;
|
||||
|
||||
// add target command T
|
||||
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() {
|
||||
|
||||
// open loop velocity movement
|
||||
// using motor.voltage_limit
|
||||
motor.move();
|
||||
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
@@ -0,0 +1,57 @@
|
||||
// 6pwm standalone example code for Teensy 4.x boards
|
||||
//
|
||||
// Teensy4.x 6pwm driver generates a 6pwm signal using FlexTimers and it doesn't support the QuadTimers
|
||||
// - Each high-low pair of the 6pwm has to be A and B channels of the same FlexTimer and to the same submodule
|
||||
//
|
||||
// List of available teensy 4.1 pins with their respective submodules and channels
|
||||
// FlexPWM(timer number)_(submodule)_(channel)
|
||||
// FlexPWM4_2_A pin 2
|
||||
// FlexPWM4_2_B pin 3
|
||||
// FlexPWM1_3_B pin 7
|
||||
// FlexPWM1_3_A pin 8
|
||||
// FlexPWM2_2_A pin 6
|
||||
// FlexPWM2_2_B pin 9
|
||||
// FlexPWM3_1_B pin 28
|
||||
// FlexPWM3_1_A pin 29
|
||||
// FlexPWM2_3_A pin 36
|
||||
// FlexPWM2_3_B pin 37
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
|
||||
// BLDC driver instance
|
||||
// make sure to provide channel A for high side and channel B for low side
|
||||
// BLDCDriver6PWM(pwmA_H, pwmA_L, pwmB_H,pwmB_L, pwmC_H, pwmC_L)
|
||||
// Example configuration
|
||||
BLDCDriver6PWM driver = BLDCDriver6PWM(2,3, 6,9, 8,7);
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
// Enable debugging
|
||||
// Driver init will show debugging output
|
||||
SimpleFOCDebug::enable(&Serial);
|
||||
|
||||
// pwm frequency to be used [Hz]
|
||||
driver.pwm_frequency = 30000;
|
||||
// dead zone percentage of the duty cycle - default 0.02 - 2%
|
||||
driver.dead_zone=0.02;
|
||||
// power supply voltage [V]
|
||||
driver.voltage_power_supply = 12;
|
||||
// Max DC voltage allowed - default voltage_power_supply
|
||||
driver.voltage_limit = 12;
|
||||
|
||||
// driver init
|
||||
driver.init();
|
||||
|
||||
// enable driver
|
||||
driver.enable();
|
||||
|
||||
_delay(1000);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// setting pwm
|
||||
// phase A: 3V
|
||||
// phase B: 6V
|
||||
// phase C: 5V
|
||||
driver.setPwm(3,6,5);
|
||||
}
|
||||
@@ -0,0 +1,80 @@
|
||||
// 6pwm openloop velocity example
|
||||
//
|
||||
// Teensy4.x 6pwm driver generates a 6pwm signal using FlexTimers and it doesn't support the QuadTimers
|
||||
// - Each high-low pair of the 6pwm has to be A and B channels of the same FlexTimer and to the same submodule
|
||||
//
|
||||
// List of available teensy 4.1 pins with their respective submodules and channels
|
||||
// FlexPWM(timer number)_(submodule)_(channel)
|
||||
// FlexPWM4_2_A pin 2
|
||||
// FlexPWM4_2_B pin 3
|
||||
// FlexPWM1_3_B pin 7
|
||||
// FlexPWM1_3_A pin 8
|
||||
// FlexPWM2_2_A pin 6
|
||||
// FlexPWM2_2_B pin 9
|
||||
// FlexPWM3_1_B pin 28
|
||||
// FlexPWM3_1_A pin 29
|
||||
// FlexPWM2_3_A pin 36
|
||||
// FlexPWM2_3_B pin 37
|
||||
#include <SimpleFOC.h>
|
||||
|
||||
|
||||
// BLDC motor & driver instance
|
||||
// BLDCMotor motor = BLDCMotor(pole pair number);
|
||||
BLDCMotor motor = BLDCMotor(11);
|
||||
// make sure to provide channel A for high side and channel B for low side
|
||||
// BLDCDriver6PWM(pwmA_H, pwmA_L, pwmB_H,pwmB_L, pwmC_H, pwmC_L)
|
||||
// Example configuration
|
||||
BLDCDriver6PWM driver = BLDCDriver6PWM(2,3, 6,9, 8,7);
|
||||
|
||||
// instantiate the commander
|
||||
Commander command = Commander(Serial);
|
||||
void doTarget(char* cmd) { command.scalar(&motor.target, cmd); }
|
||||
void doLimit(char* cmd) { command.scalar(&motor.voltage_limit, cmd); }
|
||||
|
||||
void setup() {
|
||||
|
||||
// driver config
|
||||
// power supply voltage [V]
|
||||
driver.voltage_power_supply = 12;
|
||||
// limit the maximal dc voltage the driver can set
|
||||
// as a protection measure for the low-resistance motors
|
||||
// this value is fixed on startup
|
||||
driver.voltage_limit = 6;
|
||||
driver.init();
|
||||
// link the motor and the driver
|
||||
motor.linkDriver(&driver);
|
||||
|
||||
// limiting motor movements
|
||||
// limit the voltage to be set to the motor
|
||||
// start very low for high resistance motors
|
||||
// currnet = resistance*voltage, so try to be well under 1Amp
|
||||
motor.voltage_limit = 3; // [V]
|
||||
|
||||
// open loop control config
|
||||
motor.controller = MotionControlType::velocity_openloop;
|
||||
|
||||
// init motor hardware
|
||||
motor.init();
|
||||
|
||||
//initial motor target
|
||||
motor.target=0;
|
||||
|
||||
// add target command T
|
||||
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() {
|
||||
|
||||
// open loop velocity movement
|
||||
// using motor.voltage_limit
|
||||
motor.move();
|
||||
|
||||
// user communication
|
||||
command.run();
|
||||
}
|
||||
Reference in New Issue
Block a user