try to fix submodule

This commit is contained in:
2023-11-09 19:02:15 -05:00
parent c1d45aa443
commit deea94b076
366 changed files with 40228 additions and 2 deletions

View File

@@ -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(&currentSense);
// 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();
}

View File

@@ -0,0 +1 @@
-DHAL_OPAMP_MODULE_ENABLED

View File

@@ -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();
}

View File

@@ -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();
}

View File

@@ -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();
}

View File

@@ -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();
}

View File

@@ -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();
}

View File

@@ -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();
}

View File

@@ -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();
}

View File

@@ -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();
}

View File

@@ -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();
}

View File

@@ -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();
}

View File

@@ -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(&current_sense);
// init FOC
motor.initFOC();
delay(1000);
}
void loop(){
// foc loop
motor.loopFOC();
// motion control
motor.move();
// monitoring
motor.monitor();
// user communication
command.run();
}

View File

@@ -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(&current_sense);
// init FOC
motor.initFOC();
delay(1000);
}
void loop(){
// foc loop
motor.loopFOC();
// motion control
motor.move();
// monitoring
motor.monitor();
// user communication
command.run();
}

View File

@@ -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

View File

@@ -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();
}

View File

@@ -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(&current_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();
}

View File

@@ -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();
}

View File

@@ -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();
}

View File

@@ -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();
}

View File

@@ -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(&current_sense1);
// current sense init and linking
current_sense2.init();
motor2.linkCurrentSense(&current_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();
}

View File

@@ -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(&current_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();
}

View File

@@ -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(&current_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();
}

View File

@@ -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();
}

View File

@@ -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);
}

View File

@@ -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();
}

View File

@@ -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);
}

View File

@@ -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();
}

View File

@@ -0,0 +1,70 @@
// Open loop motor control example
#include <SimpleFOC.h>
// BLDC motor & driver instance
// BLDCMotor motor = BLDCMotor(pole pair number);
BLDCMotor motor = BLDCMotor(11);
// BLDCDriver3PWM driver = BLDCDriver3PWM(pwmA, pwmB, pwmC, Enable(optional));
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
// Stepper motor & driver instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
//target variable
float target_position = 0;
// instantiate the commander
Commander command = Commander(Serial);
void doTarget(char* cmd) { command.scalar(&target_position, cmd); }
void doLimit(char* cmd) { command.scalar(&motor.voltage_limit, cmd); }
void doVelocity(char* cmd) { command.scalar(&motor.velocity_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]
// limit/set the velocity of the transition in between
// target angles
motor.velocity_limit = 5; // [rad/s] cca 50rpm
// open loop control config
motor.controller = MotionControlType::angle_openloop;
// init motor hardware
motor.init();
// add target command T
command.add('T', doTarget, "target angle");
command.add('L', doLimit, "voltage limit");
command.add('V', doLimit, "movement velocity");
Serial.begin(115200);
Serial.println("Motor ready!");
Serial.println("Set target position [rad]");
_delay(1000);
}
void loop() {
// open loop angle movements
// using motor.voltage_limit and motor.velocity_limit
// angles can be positive or negative, negative angles correspond to opposite motor direction
motor.move(target_position);
// user communication
command.run();
}

View File

@@ -0,0 +1,68 @@
// Open loop motor control example
#include <SimpleFOC.h>
// BLDC motor & driver instance
// BLDCMotor motor = BLDCMotor(pole pair number);
BLDCMotor motor = BLDCMotor(11);
// BLDCDriver3PWM driver = BLDCDriver3PWM(pwmA, pwmB, pwmC, Enable(optional));
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
// Stepper motor & driver instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
//target variable
float target_velocity = 0;
// instantiate the commander
Commander command = Commander(Serial);
void doTarget(char* cmd) { command.scalar(&target_velocity, cmd); }
void doLimit(char* cmd) { command.scalar(&motor.voltage_limit, cmd); }
void setup() {
// driver 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
// current = voltage / resistance, 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();
// 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 and motor.velocity_limit
// to turn the motor "backwards", just set a negative target_velocity
motor.move(target_velocity);
// user communication
command.run();
}

View File

@@ -0,0 +1,129 @@
/**
*
* Position/angle motion control example
* Steps:
* 1) Configure the motor and encoder
* 2) Run the code
* 3) Set the target angle (in radians) from serial terminal
*
*
* NOTE :
* > Arduino UNO example code for running velocity motion control using an encoder with index significantly
* > Since Arduino UNO doesn't have enough interrupt pins we have to use software interrupt library PciManager.
*
* > If running this code with Nucleo or Bluepill or any other board which has more than 2 interrupt pins
* > you can supply doIndex directly to the encoder.enableInterrupts(doA,doB,doIndex) and avoid using PciManger
*
* > If you don't want to use index pin initialize the encoder class without index pin number:
* > For example:
* > - Encoder encoder = Encoder(2, 3, 8192);
* > and initialize interrupts like this:
* > - encoder.enableInterrupts(doA,doB)
*
* Check the docs.simplefoc.com for more info about the possible encoder configuration.
*
*/
#include <SimpleFOC.h>
// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(11);
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
// Stepper motor & driver instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
// encoder instance
Encoder encoder = Encoder(2, 3, 8192);
// 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;
// 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 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();
}

View File

@@ -0,0 +1,133 @@
/**
*
* Position/angle motion control example
* Steps:
* 1) Configure the motor and hall sensor
* 2) Run the code
* 3) Set the target angle (in radians) from serial terminal
*
*
* NOTE :
* > This is for Arduino UNO example code for running angle motion control specifically
* > Since Arduino UNO doesn't have enough interrupt pins we have to use software interrupt library PciManager.
*
* > If running this code with Nucleo or Bluepill or any other board which has more than 2 interrupt pins
* > you can supply doIndex directly to the sensr.enableInterrupts(doA,doB,doC) and avoid using PciManger
*
*
*/
#include <SimpleFOC.h>
// software interrupt library
#include <PciManager.h>
#include <PciListenerImp.h>
// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(11);
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
// Stepper motor & driver instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
// hall sensor instance
HallSensor sensor = HallSensor(2, 3, 4, 11);
// Interrupt routine intialisation
// channel A and B callbacks
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
void doC(){sensor.handleC();}
// If no available hadware interrupt pins use the software interrupt
PciListenerImp listenC(sensor.pinC, doC);
// 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 sensor hardware
sensor.init();
sensor.enableInterrupts(doA, doB); //, doC);
// software interrupts
PciManager.registerListener(&listenC);
// 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);
// 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 = 2;
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 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();
}

View File

@@ -0,0 +1,112 @@
/**
*
* Position/angle motion control example
* Steps:
* 1) Configure the motor and magnetic sensor
* 2) Run the code
* 3) Set the target angle (in radians) from serial terminal
*
*/
#include <SimpleFOC.h>
// magnetic sensor instance - SPI
MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, 10);
// magnetic sensor instance - MagneticSensorI2C
//MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);
// magnetic sensor instance - analog output
// MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020);
// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(11);
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
// Stepper motor & driver instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
// 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;
motor.PID_velocity.D = 0;
// 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 = 20;
// 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();
}

View File

@@ -0,0 +1,107 @@
/**
*
* Torque control example using current control loop.
*
*/
#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();}
// current sensor
InlineCurrentSense current_sense = InlineCurrentSense(0.01f, 50.0f, A0, A2);
// current set point variable
float target_current = 0;
// instantiate the commander
Commander command = Commander(Serial);
void doTarget(char* cmd) { command.scalar(&target_current, 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);
// current sense init hardware
current_sense.init();
// link the current sense to the motor
motor.linkCurrentSense(&current_sense);
// set torque mode:
// TorqueControlType::dc_current
// TorqueControlType::voltage
// TorqueControlType::foc_current
motor.torque_controller = TorqueControlType::foc_current;
// set motion control loop to be used
motor.controller = MotionControlType::torque;
// foc currnet control parameters (Arduino UNO/Mega)
motor.PID_current_q.P = 5;
motor.PID_current_q.I= 300;
motor.PID_current_d.P= 5;
motor.PID_current_d.I = 300;
motor.LPF_current_q.Tf = 0.01f;
motor.LPF_current_d.Tf = 0.01f;
// foc currnet control parameters (stm/esp/due/teensy)
// motor.PID_current_q.P = 5;
// motor.PID_current_q.I= 1000;
// motor.PID_current_d.P= 5;
// motor.PID_current_d.I = 1000;
// motor.LPF_current_q.Tf = 0.002f; // 1ms default
// motor.LPF_current_d.Tf = 0.002f; // 1ms default
// 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 current");
Serial.println(F("Motor ready."));
Serial.println(F("Set the target current 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 torque (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_current);
// user communication
command.run();
}

View File

@@ -0,0 +1,92 @@
/**
*
* Torque control example using voltage control loop.
*
* 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.
*/
#include <SimpleFOC.h>
// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(11);
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
// Stepper motor & driver instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
// encoder instance
Encoder encoder = Encoder(2, 3, 8192);
// Interrupt routine intialisation
// channel A and B callbacks
void doA(){encoder.handleA();}
void doB(){encoder.handleB();}
// 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();
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);
// aligning voltage
motor.voltage_sensor_align = 5;
// choose FOC modulation (optional)
motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
// set motion control loop to be used
motor.controller = MotionControlType::torque;
// 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();
}

View File

@@ -0,0 +1,95 @@
/**
*
* Torque control example using voltage control loop.
*
* 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 of the current.
*
* This makes the BLDC motor effectively a DC motor, and you can use it in a same way.
*/
#include <SimpleFOC.h>
// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(11);
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
// Stepper motor & driver instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
// hall sensor instance
HallSensor sensor = HallSensor(2, 3, 4, 11);
// Interrupt routine intialisation
// channel A and B callbacks
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
void doC(){sensor.handleC();}
// 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
sensor.init();
sensor.enableInterrupts(doA, doB, doC);
// link the motor to the sensor
motor.linkSensor(&sensor);
// driver config
// power supply voltage [V]
driver.voltage_power_supply = 12;
driver.init();
// link driver
motor.linkDriver(&driver);
// aligning voltage
motor.voltage_sensor_align = 3;
// choose FOC modulation (optional)
motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
// set motion control loop to be used
motor.controller = MotionControlType::torque;
// 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();
}

View File

@@ -0,0 +1,84 @@
/**
* Torque control example using voltage control loop.
*
* 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.
*/
#include <SimpleFOC.h>
// magnetic sensor instance - SPI
MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, 10);
// magnetic sensor instance - I2C
// MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);
// magnetic sensor instance - analog output
// MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020);
// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(11);
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
// Stepper motor & driver instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
// 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() {
// 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);
// aligning voltage
motor.voltage_sensor_align = 5;
// choose FOC modulation (optional)
motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
// set motion control loop to be used
motor.controller = MotionControlType::torque;
// 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();
}

View File

@@ -0,0 +1,137 @@
/**
*
* Velocity motion control example
* Steps:
* 1) Configure the motor and encoder
* 2) Run the code
* 3) Set the target velocity (in radians per second) from serial terminal
*
*
*
* NOTE :
* > Arduino UNO example code for running velocity motion control using an encoder with index significantly
* > Since Arduino UNO doesn't have enough interrupt pins we have to use software interrupt library PciManager.
*
* > If running this code with Nucleo or Bluepill or any other board which has more than 2 interrupt pins
* > you can supply doIndex directly to the encoder.enableInterrupts(doA,doB,doIndex) and avoid using PciManger
*
* > If you don't want to use index pin initialize the encoder class without index pin number:
* > For example:
* > - Encoder encoder = Encoder(2, 3, 8192);
* > and initialize interrupts like this:
* > - encoder.enableInterrupts(doA,doB)
*
* Check the docs.simplefoc.com for more info about the possible encoder configuration.
*
*/
#include <SimpleFOC.h>
// software interrupt library
#include <PciManager.h>
#include <PciListenerImp.h>
// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(11);
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
// Stepper motor & driver instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
// encoder instance
Encoder encoder = Encoder(2, 3, 8192, A0);
// Interrupt routine intialisation
// channel A and B callbacks
void doA(){encoder.handleA();}
void doB(){encoder.handleB();}
void doIndex(){encoder.handleIndex();}
// If no available hadware interrupt pins use the software interrupt
PciListenerImp listenerIndex(encoder.index_pin, doIndex);
// velocity set point variable
float target_velocity = 0;
// instantiate the commander
Commander command = Commander(Serial);
void doTarget(char* cmd) { command.scalar(&target_velocity, cmd); }
void setup() {
// initialize encoder sensor hardware
encoder.init();
encoder.enableInterrupts(doA, doB);
// software interrupts
PciManager.registerListener(&listenerIndex);
// 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;
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;
// 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 velocity");
Serial.println(F("Motor ready."));
Serial.println(F("Set the target velocity 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_velocity);
// function intended to be used with serial plotter to monitor motor variables
// significantly slowing the execution down!!!!
// motor.monitor();
// user communication
command.run();
}

View File

@@ -0,0 +1,125 @@
/**
*
* Velocity motion control example
* Steps:
* 1) Configure the motor and sensor
* 2) Run the code
* 3) Set the target velocity (in radians per second) from serial terminal
*
*
*
* NOTE :
* > Specifically for Arduino UNO example code for running velocity motion control using a hall sensor
* > Since Arduino UNO doesn't have enough interrupt pins we have to use software interrupt library PciManager.
*
* > If running this code with Nucleo or Bluepill or any other board which has more than 2 interrupt pins
* > you can supply doC directly to the sensor.enableInterrupts(doA,doB,doC) and avoid using PciManger
*
*/
#include <SimpleFOC.h>
// software interrupt library
#include <PciManager.h>
#include <PciListenerImp.h>
// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(11);
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
// Stepper motor & driver instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
// hall sensor instance
HallSensor sensor = HallSensor(2, 3, 4, 11);
// Interrupt routine intialisation
// channel A and B callbacks
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
void doC(){sensor.handleC();}
// If no available hadware interrupt pins use the software interrupt
PciListenerImp listenerIndex(sensor.pinC, doC);
// velocity set point variable
float target_velocity = 0;
// instantiate the commander
Commander command = Commander(Serial);
void doTarget(char* cmd) { command.scalar(&target_velocity, cmd); }
void setup() {
// initialize sensor sensor hardware
sensor.init();
sensor.enableInterrupts(doA, doB); //, doC);
// software interrupts
PciManager.registerListener(&listenerIndex);
// 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);
// aligning voltage [V]
motor.voltage_sensor_align = 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 = 2;
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;
// 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 velocity 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_velocity);
// function intended to be used with serial plotter to monitor motor variables
// significantly slowing the execution down!!!!
// motor.monitor();
// user communication
command.run();
}

View File

@@ -0,0 +1,106 @@
/**
*
* Velocity motion control example
* Steps:
* 1) Configure the motor and magnetic sensor
* 2) Run the code
* 3) Set the target velocity (in radians per second) from serial terminal
*
*
* By using the serial terminal set the velocity value you want to motor to obtain
*
*/
#include <SimpleFOC.h>
// magnetic sensor instance - SPI
MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, 10);
// magnetic sensor instance - MagneticSensorI2C
//MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);
// MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020);
// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(11);
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
// Stepper motor & driver instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
// velocity set point variable
float target_velocity = 0;
// instantiate the commander
Commander command = Commander(Serial);
void doTarget(char* cmd) { command.scalar(&target_velocity, 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);
// 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;
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
// default 5ms - try different values to see what is the best.
// the lower the less filtered
motor.LPF_velocity.Tf = 0.01f;
// 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 velocity");
Serial.println(F("Motor ready."));
Serial.println(F("Set the target velocity 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_velocity);
// function intended to be used with serial plotter to monitor motor variables
// significantly slowing the execution down!!!!
// motor.monitor();
// user communication
command.run();
}

View File

@@ -0,0 +1,106 @@
/**
* Comprehensive BLDC motor control example using encoder
*
* 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
*
* See more info in docs.simplefoc.com/commander_interface
*/
#include <SimpleFOC.h>
// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(11);
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
// Stepper motor & driver instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
// 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);
// driver config
// power supply voltage [V]
driver.voltage_power_supply = 12;
driver.init();
// link 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;
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 = 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");
// 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
// velocity, position or voltage
// if tatget not set in parameter uses motor.target variable
motor.move();
// user communication
command.run();
}

View File

@@ -0,0 +1,114 @@
/**
* Comprehensive BLDC motor control example using Hall sensor
*
* 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
*
* See more info in docs.simplefoc.com/commander_interface
*/
#include <SimpleFOC.h>
// software interrupt library
#include <PciManager.h>
#include <PciListenerImp.h>
// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(11);
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
// Stepper motor & driver instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
// hall sensor instance
HallSensor sensor = HallSensor(2, 3, 4, 11);
// Interrupt routine intialisation
// channel A, B and C callbacks
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
void doC(){sensor.handleC();}
// If no available hadware interrupt pins use the software interrupt
PciListenerImp listenC(sensor.pinC, doC);
// commander interface
Commander command = Commander(Serial);
void onMotor(char* cmd){ command.motor(&motor, cmd); }
void setup() {
// initialize encoder sensor hardware
sensor.init();
sensor.enableInterrupts(doA, doB); //, doC);
// software interrupts
PciManager.registerListener(&listenC);
// link the motor to the sensor
motor.linkSensor(&sensor);
// driver config
// power supply voltage [V]
driver.voltage_power_supply = 12;
driver.init();
// link 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;
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 = 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");
// 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
// velocity, position or voltage
// if tatget not set in parameter uses motor.target variable
motor.move();
// user communication
command.run();
}

View File

@@ -0,0 +1,104 @@
/**
* Comprehensive BLDC motor control example using magnetic sensor
*
* 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
*
* See more info in docs.simplefoc.com/commander_interface
*/
#include <SimpleFOC.h>
// magnetic sensor instance - SPI
MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, 10);
// magnetic sensor instance - MagneticSensorI2C
//MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);
// magnetic sensor instance - analog output
// MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020);
// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(11);
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
// Stepper motor & driver instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
// commander interface
Commander command = Commander(Serial);
void onMotor(char* cmd){ command.motor(&motor, 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 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 control type
motor.PID_velocity.P = 0.2f;
motor.PID_velocity.I = 20;
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 = 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");
// 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
// velocity, position or voltage
// if tatget not set in parameter uses motor.target variable
motor.move();
// user communication
command.run();
}

View File

@@ -0,0 +1,28 @@
# OSC control examples
OSC - opensoundcontrol.org is a simple message exchange protocol. Widely used in the Audio world it is being hailed as the successor to MIDI. But MIDI itself, and now OSC, has always been about sending and receiving fairly simple control messages, at medium speed, and that makes it well suited for the same kind of task in robotics or other control applications.
As a protocol it is simple, making implementation quite easy, and while binary, simple enough to be fairly "human readable", which aids in debugging and reduces errors.
The main advantage of using it is that there is a bunch of ready made software, and also libraries to use in your own programs, neaning you don't have to re-invent these things from scratch.
## TouchOSC
The first example shows how to set up control of a motor from TouchOSC. It's a super-fast way to set up a customizable GUI for your motor-project, that runs on your phone...
## purr-Data
The second example, "simplefoc\_osc\_esp32\_fullcontrol.ino" allows setting the variables and tuning the motor parameters, in the same way as the serial control but via OSC. The file "osc\_fullcontrol.pd" contains a sample GUI to go with that sketch, allowing the control and tuning of 2 BLDC motors.
Here a screenshot of what it looks like in purr-Data:
![Screenshot from pD](osc_fullcontrol_screenshot.png?raw=true "pD controlling 2 BLDC motors")
## Links to software used in examples
- OSC - opensoundcontrol.org
- pD - https://puredata.info
- TouchOSC - https://hexler.net/products/touchosc

View File

@@ -0,0 +1,183 @@
/**
* Arduino SimpleFOC + OSC control example
*
* Simple example to show how you can control SimpleFOC via OSC.
*
* It's a nice way to work, easier than changing speeds via Seerial text input. It could also be the basis for
* a functional UI, for example in a lab, art-gallery or similar situation.
*
* For this example we used an ESP32 to run the code, a AS5048B I2C absolute encoder
* and a generic L298 driver board to drive a Emax 4114 gimbal motor. But there is no reason the OSC part will
* not work with any other setup.
*
* You will need:
*
* - a working SimpleFOC setup - motor, driver, encoder
* - a MCU with WiFi and UDP support, for example an ESP32, or an Arduino with Ethernet Shield
* - a device to run an OSC UI
* - a configured OSC UI
* - a WiFi network
*
* To do the OSC UI I used TouchOSC from https://hexler.net/products/touchosc
* There is an example UI file that works with this sketch, see "layout1.touchosc"
* You can open the UI file in 'TouchOSC Editor' (free program) and transfer it to the TouchOSC app on your device.
*
* Alternatively, there are other OSC UIs which may work, e.g. http://opensoundcontrol.org/implementations
*
* Using:
*
* Change the values below to match the WiFi ssid/password of your network.
* Load and run the code on your ESP32. Take a note of the IP address of your ESP32.
* Load and run the UI in TouchOSC.
* Configure TouchOSC to connect to your ESP32.
* The first command you send will cause the ESP32 to start sending responses to your TouchOSC device.
* After this you will see motor position and speed in the UI.
* Have fun controlling your SimpleFOC motors from your smartphone!
*
*/
#include "Arduino.h"
#include <SimpleFOC.h>
#include <WiFi.h>
#include <WiFiUdp.h>
#include <OSCMessage.h>
#include <OSCBundle.h>
#include <OSCBoards.h>
#include <Math.h>
const char ssid[] = "myssid"; // your network SSID (name)
const char pass[] = "mypassword"; // your network password
WiFiUDP Udp;
IPAddress outIp(192,168,1,17); // remote IP (not needed for receive)
const unsigned int outPort = 8000; // remote port (not needed for receive)
const unsigned int inPort = 8000; // local port to listen for UDP packets (here's where we send the packets)
OSCErrorCode error;
MagneticSensorI2C sensor = MagneticSensorI2C(0x40, 14, 0xFE, 8);
BLDCMotor motor = BLDCMotor(11);
BLDCDriver3PWM driver = BLDCDriver3PWM(25, 26, 27);
// commander interface
Commander command = Commander(Serial);
void setup() {
Serial.begin(115200);
WiFi.begin(ssid, pass);
Serial.print("Connecting WiFi ");
Serial.println(ssid);
while (WiFi.status() != WL_CONNECTED) {
delay(500);
Serial.print(".");
}
Udp.begin(inPort);
Serial.println();
Serial.print("WiFi connected. Local OSC address: ");
Serial.print(WiFi.localIP());
Serial.print(":");
Serial.println(inPort);
delay(2000);
Serial.println("Initializing motor.");
sensor.init();
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 = 8;
//motor.P_angle.P = 20;
motor.init();
motor.initFOC();
Serial.println("All initialization complete.");
}
// velocity set point variable
float target_velocity = 2.0f;
// angle set point variable
float target_angle = 1.0f;
void motorControl(OSCMessage &msg){
if (msg.isInt(0))
target_velocity = radians(msg.getInt(0));
else if (msg.isFloat(0))
target_velocity = radians(msg.getFloat(0));
else if (msg.isDouble(0))
target_velocity = radians(msg.getDouble(0));
Serial.print("Velocity set to ");
Serial.println(target_velocity);
}
void cmdControl(OSCMessage &msg){
char cmdStr[16];
if (msg.isString(0)) {
msg.getString(0,cmdStr,16);
command.motor(&motor,cmdStr);
}
}
long lastSend = 0;
OSCMessage bundleIN;
void loop() {
OSCBundle bundleOUT;
// FOC algorithm function
motor.move(target_velocity);
motor.loopFOC();
int size = Udp.parsePacket();
if (size > 0) {
while (size--) {
bundleIN.fill(Udp.read());
}
if (!bundleIN.hasError()) {
bundleIN.dispatch("/mot1/S", motorControl);
bundleIN.dispatch("/mot1/C", cmdControl);
IPAddress ip = Udp.remoteIP();
if (!( ip==outIp )) {
Serial.print("New connection from ");
Serial.println(ip);
outIp = ip;
}
}
else {
error = bundleIN.getError();
Serial.print("error: ");
Serial.println(error);
}
bundleIN.empty();
}
else { // don't receive and send in the same loop...
long now = millis();
if (now - lastSend > 100) {
int ang = (int)degrees(motor.shaftAngle()) % 360;
if (ang<0) ang = 360-abs(ang);
//BOSCBundle's add' returns the OSCMessage so the message's 'add' can be composed together
bundleOUT.add("/mot1/A").add((int)ang);
bundleOUT.add("/mot1/V").add((int)degrees(motor.shaftVelocity()));
Udp.beginPacket(outIp, outPort);
bundleOUT.send(Udp);
Udp.endPacket();
bundleOUT.empty(); // empty the bundle to free room for a new one
lastSend = now;
}
}
}

View File

@@ -0,0 +1,351 @@
/**
*
* Control 2 motors on ESP32 using OSC
*
* In this example, all the commands available on the serial command interface are also available via OSC.
* Also, the example is for 2 motors. If you have only 1 motor, comment out the lines for the second motor.
*
*
*
*
*/
#include "Arduino.h"
#include <Wire.h>
#include <SimpleFOC.h>
#include "ssid.h" // create this file, which defines the constants MYSSID and MYPASS
#include <Wifi.h>
#include <WiFiUdp.h>
#include <ArduinoOTA.h>
#include <OSCMessage.h>
#include <OSCBundle.h>
#include <OSCBoards.h>
const char ssid[] = MYSSID; // your network SSID (name)
const char pass[] = MYPASS; // your network password
WiFiUDP Udp;
IPAddress outIp(192,168,1,13); // remote IP (not needed for receive)
const unsigned int outPort = 8000; // remote port (not needed for receive)
const unsigned int inPort = 8000; // local port to listen for UDP packets (here's where we send the packets)
#define POWER_SUPPLY 7.4f
MagneticSensorI2C sensor2 = MagneticSensorI2C(0x40, 14, 0xFE, 8);
MagneticSensorI2C sensor1 = MagneticSensorI2C(0x41, 14, 0xFE, 8);
BLDCMotor motor1 = BLDCMotor(7);
BLDCMotor motor2 = BLDCMotor(7);
BLDCDriver3PWM driver1 = BLDCDriver3PWM(25, 26, 27);
BLDCDriver3PWM driver2 = BLDCDriver3PWM(0, 4, 16);
String m1Prefix("/M1");
String m2Prefix("/M2");
// we store seperate set-points for each motor, of course
float set_point1 = 0.0f;
float set_point2 = 0.0f;
OSCErrorCode error;
OSCBundle bundleOUT; // outgoing message, gets re-used
void setupOTA(const char* hostname) {
ArduinoOTA
.setPort(8266)
.onStart([]() {
String type;
if (ArduinoOTA.getCommand() == U_FLASH)
type = "sketch";
else // U_SPIFFS
type = "filesystem";
// NOTE: if updating SPIFFS this would be the place to unmount SPIFFS using SPIFFS.end()
Serial.println("Start updating " + type);
})
.onEnd([]() {
Serial.println("\nEnd");
})
.onProgress([](unsigned int progress, unsigned int total) {
Serial.printf("Progress: %u%%\n", (progress / (total / 100)));
})
.onError([](ota_error_t error) {
Serial.printf("Error[%u]: ", error);
if (error == OTA_AUTH_ERROR) Serial.println("Auth Failed");
else if (error == OTA_BEGIN_ERROR) Serial.println("Begin Failed");
else if (error == OTA_CONNECT_ERROR) Serial.println("Connect Failed");
else if (error == OTA_RECEIVE_ERROR) Serial.println("Receive Failed");
else if (error == OTA_END_ERROR) Serial.println("End Failed");
})
.setHostname(hostname)
.setMdnsEnabled(true);
ArduinoOTA.begin();
}
void setup() {
// set pins low - motor initialization can take some time,
// and you don't want current flowing through the other motor while it happens...
pinMode(0,OUTPUT);
pinMode(4,OUTPUT);
pinMode(16,OUTPUT);
pinMode(25,OUTPUT);
pinMode(26,OUTPUT);
pinMode(27,OUTPUT);
digitalWrite(0, 0);
digitalWrite(4, 0);
digitalWrite(16, 0);
digitalWrite(25, 0);
digitalWrite(26, 0);
digitalWrite(27, 0);
Serial.begin(115200);
delay(200);
WiFi.begin(ssid, pass);
Serial.print("Connecting WiFi ");
Serial.println(ssid);
while (WiFi.status() != WL_CONNECTED) {
delay(500);
Serial.print(".");
}
Udp.begin(inPort);
Serial.println();
Serial.print("WiFi connected. Local OSC address: ");
Serial.print(WiFi.localIP());
Serial.print(":");
Serial.println(inPort);
setupOTA("smallrobot1");
Serial.println("Initializing motors.");
Wire.setClock(400000);
sensor1.init();
motor1.linkSensor(&sensor1);
driver1.voltage_power_supply = POWER_SUPPLY;
driver1.init();
motor1.linkDriver(&driver1);
motor1.foc_modulation = FOCModulationType::SpaceVectorPWM;
motor1.controller = MotionControlType::velocity;
motor1.PID_velocity.P = 0.2f;
motor1.PID_velocity.I = 20;
motor1.PID_velocity.D = 0.001f;
motor1.PID_velocity.output_ramp = 1000;
motor1.LPF_velocity.Tf = 0.01f;
motor1.voltage_limit = POWER_SUPPLY;
motor1.P_angle.P = 20;
motor1.init();
motor1.initFOC();
sensor2.init();
motor2.linkSensor(&sensor2);
driver2.voltage_power_supply = POWER_SUPPLY;
driver2.init();
motor2.linkDriver(&driver2);
motor2.foc_modulation = FOCModulationType::SpaceVectorPWM;
motor2.controller = MotionControlType::velocity;
motor2.PID_velocity.P = 0.2f;
motor2.PID_velocity.I = 20;
motor2.PID_velocity.D = 0.001f;
motor2.PID_velocity.output_ramp = 1000;
motor2.LPF_velocity.Tf = 0.01f;
motor2.voltage_limit = POWER_SUPPLY;
motor2.P_angle.P = 20;
motor2.init();
motor2.initFOC();
sendMotorParams(motor1, m1Prefix);
sendMotorParams(motor2, m2Prefix);
Serial.println("All initialization complete.");
_delay(1000);
}
template <typename T>
void sendMessage(String& addr, T datum) {
bundleOUT.add(addr.c_str()).add(datum);
Udp.beginPacket(outIp, outPort);
bundleOUT.send(Udp);
Udp.endPacket();
bundleOUT.empty(); // empty the bundle to free room for a new one
}
float getNumber(OSCMessage &msg, int index) {
if (msg.getType(index)=='i')
return msg.getInt(index);
if (msg.getType(index)=='f')
return msg.getFloat(index);
if (msg.getType(index)=='d')
return msg.getDouble(index);
return 0;
}
void motorCmd(OSCMessage &msg, int offset, BLDCMotor& motor, float* set_point, String& prefix){
Serial.print("Command for ");
Serial.println(prefix);
if (msg.fullMatch("/P", offset)) {
motor.PID_velocity.P = getNumber(msg,0);
sendMessage(prefix+"/P", motor.PID_velocity.P);
}
else if (msg.fullMatch("/I", offset)) {
motor.PID_velocity.I = getNumber(msg,0);
sendMessage(prefix+"/I", motor.PID_velocity.I);
}
else if (msg.fullMatch("/D", offset)) {
motor.PID_velocity.D = getNumber(msg,0);
sendMessage(prefix+"/D", motor.PID_velocity.D);
}
else if (msg.fullMatch("/R", offset)) {
motor.PID_velocity.output_ramp = getNumber(msg,0);
sendMessage(prefix+"/R", motor.PID_velocity.output_ramp);
}
else if (msg.fullMatch("/F", offset)) {
motor.LPF_velocity.Tf = getNumber(msg,0);
sendMessage(prefix+"/F", motor.LPF_velocity.Tf);
}
else if (msg.fullMatch("/K", offset)) {
motor.P_angle.P = getNumber(msg,0);
sendMessage(prefix+"/K", motor.P_angle.P);
}
else if (msg.fullMatch("/N", offset)) {
motor.velocity_limit = getNumber(msg,0);
sendMessage(prefix+"/N", motor.velocity_limit);
}
else if (msg.fullMatch("/L", offset)) {
motor.voltage_limit = getNumber(msg,0);
sendMessage(prefix+"/L", motor.voltage_limit);
}
else if (msg.fullMatch("/C", offset)) {
motor.controller = (MotionControlType)msg.getInt(0);
sendMessage(prefix+"/C", motor.controller);
}
else if (msg.fullMatch("/t", offset)) {
*set_point = getNumber(msg,0);
sendMessage(prefix+"/3", *set_point); // TODO is the set-point the same as motor.target?
Serial.print("Setting set-point to ");
Serial.println(*set_point);
}
else if (msg.fullMatch("/o", offset)) {
motor.disable();
}
else if (msg.fullMatch("/e", offset)) {
motor.enable();
}
else if (msg.fullMatch("/params", offset)) {
sendMotorParams(motor, prefix);
}
else if (msg.fullMatch("/reinit", offset)) {
motor.disable();
motor.init();
motor.initFOC();
}
}
void sendMotorMonitoring() {
//Serial.println("Sending monitoring...");
bundleOUT.add("/M1/0").add(motor1.voltage.q);
bundleOUT.add("/M1/1").add(motor1.shaft_velocity);
bundleOUT.add("/M1/2").add(motor1.shaft_angle);
bundleOUT.add("/M1/3").add(motor1.target);
bundleOUT.add("/M2/0").add(motor2.voltage.q);
bundleOUT.add("/M2/1").add(motor2.shaft_velocity);
bundleOUT.add("/M2/2").add(motor2.shaft_angle);
bundleOUT.add("/M2/3").add(motor2.target);
// TODO pack it into one message bundleOUT.add("/M2/i").add(motor2.voltage_q).add(motor2.shaft_velocity).add(motor2.shaft_angle).add(motor2.target);
Udp.beginPacket(outIp, outPort);
bundleOUT.send(Udp);
Udp.endPacket();
bundleOUT.empty(); // empty the bundle to free room for a new one
}
void sendMotorParams(BLDCMotor& motor, String& prefix) {
bundleOUT.add((prefix+"/P").c_str()).add(motor.PID_velocity.P);
bundleOUT.add((prefix+"/I").c_str()).add(motor.PID_velocity.I);
bundleOUT.add((prefix+"/D").c_str()).add(motor.PID_velocity.D);
bundleOUT.add((prefix+"/R").c_str()).add(motor.PID_velocity.output_ramp);
bundleOUT.add((prefix+"/F").c_str()).add(motor.LPF_velocity.Tf);
bundleOUT.add((prefix+"/K").c_str()).add(motor.P_angle.P);
bundleOUT.add((prefix+"/N").c_str()).add(motor.velocity_limit);
bundleOUT.add((prefix+"/L").c_str()).add(motor.voltage_limit);
bundleOUT.add((prefix+"/C").c_str()).add(motor.controller);
Udp.beginPacket(outIp, outPort);
bundleOUT.send(Udp);
Udp.endPacket();
bundleOUT.empty(); // empty the bundle to free room for a new one
}
long lastSend = 0;
OSCMessage bundleIN;
int size;
void loop() {
// FOC algorithm function
motor1.loopFOC();
motor1.move(set_point1);
motor2.loopFOC();
motor2.move(set_point2);
int size = Udp.parsePacket();
if (size > 0) {
while (size--) {
bundleIN.fill(Udp.read());
}
if (!bundleIN.hasError()) {
bundleIN.route("/M1", [](OSCMessage& msg, int offset){ motorCmd(msg, offset, motor1, &set_point1, m1Prefix); }, 0);
bundleIN.route("/M2", [](OSCMessage& msg, int offset){ motorCmd(msg, offset, motor2, &set_point2, m2Prefix); }, 0);
IPAddress ip = Udp.remoteIP();
if (!( ip==outIp )) {
Serial.print("New connection from ");
Serial.println(ip);
outIp = ip;
sendMotorParams(motor1, m1Prefix);
sendMotorParams(motor2, m2Prefix);
}
}
else {
error = bundleIN.getError();
Serial.print("error: ");
Serial.println(error);
}
bundleIN.empty();
}
else { // don't receive and send in the same loop...
long now = millis();
if (now - lastSend > 100) {
sendMotorMonitoring();
lastSend = now;
}
}
ArduinoOTA.handle();
}

View File

@@ -0,0 +1,384 @@
#N struct text float x float y text t;
#N canvas 1842 146 1519 1052 12;
#X obj 501 697 cnv 15 193 209 empty empty Tuning\ M1 20 12 0 14 #e0e0e0
#404040 0;
#X obj 787 477 mrpeach/unpackOSC;
#X obj 132 586 print oscin;
#X obj 787 504 print oscout;
#X obj 723 449 spigot;
#X obj 774 452 tgl 15 1 empty empty Debug 17 7 0 10 #fcfcfc #000000
#000000 1 1;
#X msg 591 503 disconnect;
#X obj 132 558 spigot;
#X obj 114 562 tgl 15 1 empty empty Debug -34 6 0 10 #fcfcfc #000000
#000000 0 1;
#X obj 132 531 mrpeach/unpackOSC;
#X obj 673 477 mrpeach/udpsend;
#X obj 132 496 mrpeach/udpreceive 8000;
#X obj 673 422 mrpeach/packOSC;
#X obj 1043 150 hsl 249 25 -5000 5000 0 0 empty empty Set\ Point\ M1
-2 -8 0 10 #fcfcfc #000000 #000000 0 1;
#X obj 1044 197 hsl 247 25 -15 15 0 0 empty empty Set\ Point\ M2 -2
-8 0 10 #fcfcfc #000000 #000000 12300 1;
#X obj 120 153 bng 53 250 50 0 empty empty STOP 14 26 0 10 #fc1204
#000000 #ffffff;
#X obj 200 102 * 0.10472;
#X obj 202 169 hsl 235 30 -520 520 0 0 empty empty Set\ point\ (Velocity)
-2 -8 0 10 #fcfcfc #000000 #000000 11500 1;
#X obj 673 449 spigot;
#X obj 653 452 tgl 15 1 empty empty Enable\ send -71 6 0 10 #fcfcfc
#000000 #000000 1 1;
#X msg 484 478 connect 192.168.1.43 8000;
#X obj 673 395 speedlim 100;
#X obj 231 573 mrpeach/routeOSC /M1 /M2;
#X obj 231 610 mrpeach/routeOSC /0 /1 /2 /3 /P /I /D /R /F /K /N /L
/C;
#X obj 326 844 hsl 101 29 0 6.3 0 0 empty empty rad -2 -8 0 10 #fcfcfc
#000000 #000000 0 1;
#X obj 326 812 % 6.28319;
#X obj 326 704 nbx 7 27 -1e+37 1e+37 0 0 empty empty V -5 0 0 18 #fcfcfc
#000000 #000000 0.137548 256 3;
#X obj 113 804 nbx 7 27 -1e+37 1e+37 0 0 empty empty Set\ point 0 -15
0 18 #fcfcfc #000000 #000000 0 256 3;
#X obj 326 776 nbx 7 27 -1e+37 1e+37 0 0 empty empty Position -80 0
0 18 #fcfcfc #000000 #000000 -348.637 256 3;
#X obj 326 740 nbx 7 27 -1e+37 1e+37 0 0 empty empty Velocity -80 0
0 18 #fcfcfc #000000 #000000 0.0649328 256 3;
#X obj 538 747 nbx 5 14 -1e+37 1e+37 0 0 empty empty P\ gain 0 -8 0
10 #fcfcfc #000000 #000000 0.2 256 3;
#X obj 537 776 nbx 5 14 -1e+37 1e+37 0 0 empty empty I\ gain 0 -8 0
10 #fcfcfc #000000 #000000 20 256 3;
#X obj 538 808 nbx 5 14 -1e+37 1e+37 0 0 empty empty D\ gain 0 -8 0
10 #fcfcfc #000000 #000000 0.0001 256 3;
#X obj 539 838 nbx 5 14 -1e+37 1e+37 0 0 empty empty V\ Ramp 0 -8 0
10 #fcfcfc #000000 #000000 1000 256 3;
#X obj 539 868 nbx 5 14 -1e+37 1e+37 0 0 empty empty LP\ time 0 -8
0 10 #fcfcfc #000000 #000000 0.01 256 3;
#X obj 605 747 nbx 5 14 -1e+37 1e+37 0 0 empty empty angP\ gain 0 -8
0 10 #fcfcfc #000000 #000000 20 256 3;
#X obj 608 779 nbx 5 14 -1e+37 1e+37 0 0 empty empty angP\ lim 0 -8
0 10 #fcfcfc #000000 #000000 20 256 3;
#X obj 609 836 nbx 5 14 -1e+37 1e+37 0 0 empty empty V\ limit 0 -8
0 10 #fcfcfc #000000 #000000 8 256 3;
#X obj 122 278 hradio 53 0 1 3 motorselect empty empty 0 -8 0 10 #fcfcfc
#000000 #000000 0;
#X scalar text 172 305 \; \;;
#X obj 122 372 select 0 1 2;
#X msg 122 399 prefix /M?;
#X msg 149 423 prefix /M1;
#X msg 178 445 prefix /M2;
#X obj 789 422 mrpeach/packOSC;
#X obj 789 395 speedlim 100;
#X msg 592 531 typetags \$1;
#X obj 571 535 tgl 15 1 empty empty OSC\ type\ tags -80 7 0 10 #ffffff
#000000 #000000 1 1;
#X text 63 286 Choose Motor, f 7;
#X text 137 339 All, f 4;
#X text 191 339 M1, f 4;
#X text 247 339 M2, f 4;
#X text 152 77 RPM;
#X obj 1008 148 bng 29 250 50 0 empty empty STOP 2 13 0 10 #fc1204
#000000 #ffffff;
#X obj 1009 195 bng 29 250 50 0 empty empty STOP 2 13 0 10 #fc1204
#000000 #ffffff;
#X obj 74 696 hradio 53 0 1 3 empty empty empty 0 -8 0 10 #fcfcfc #000000
#000000 1;
#X text 8 711 Control;
#X text 67 752 Voltage;
#X text 124 753 Velocity;
#X text 189 754 Position;
#X obj 312 101 /;
#X obj 312 129 * 6.28319;
#X text 424 75 cm, f 4;
#X text 393 51 Wheel diameter;
#X obj 394 100 * 0.0314159;
#X msg 348 636 set \$1;
#X msg 376 637 set \$1;
#X msg 407 636 set \$1;
#X msg 435 636 set \$1;
#X msg 466 636 set \$1;
#X msg 495 636 set \$1;
#X msg 524 637 set \$1;
#X msg 554 637 set \$1;
#X msg 583 637 set \$1;
#X obj 75 898 s osctargetedout;
#X obj 75 866 prepend /M1/C;
#X obj 773 304 r osctargetedout;
#X obj 593 912 prepend /M1/K;
#X obj 602 925 prepend /M1/N;
#X obj 609 936 prepend /M1/L;
#X obj 564 976 s osctargetedout;
#X obj 1271 697 cnv 15 193 209 empty empty Tuning\ M2 20 12 0 14 #e0e0e0
#404040 0;
#X obj 1001 610 mrpeach/routeOSC /0 /1 /2 /3 /P /I /D /R /F /K /N /L
/C;
#X obj 1096 844 hsl 101 29 0 6.3 0 0 empty empty rad -2 -8 0 10 #fcfcfc
#000000 #000000 0 1;
#X obj 1096 812 % 6.28319;
#X obj 1096 704 nbx 7 27 -1e+37 1e+37 0 0 empty empty V -5 0 0 18 #fcfcfc
#000000 #000000 -0.13018 256 3;
#X obj 883 804 nbx 7 27 -1e+37 1e+37 0 0 setpointin2 empty Set\ point
0 -15 0 18 #fcfcfc #000000 #000000 0 256 3;
#X obj 1096 776 nbx 7 27 -1e+37 1e+37 0 0 empty empty Position -80
0 0 18 #fcfcfc #000000 #000000 -346.273 256 3;
#X obj 1096 740 nbx 7 27 -1e+37 1e+37 0 0 empty empty Velocity -80
0 0 18 #fcfcfc #000000 #000000 0.0657255 256 3;
#X obj 1308 747 nbx 5 14 -1e+37 1e+37 0 0 empty empty P\ gain 0 -8
0 10 #fcfcfc #000000 #000000 0.2 256 3;
#X obj 1308 778 nbx 5 14 -1e+37 1e+37 0 0 empty empty I\ gain 0 -8
0 10 #fcfcfc #000000 #000000 20 256 3;
#X obj 1308 808 nbx 5 14 -1e+37 1e+37 0 0 empty empty D\ gain 0 -8
0 10 #fcfcfc #000000 #000000 0.001 256 3;
#X obj 1309 838 nbx 5 14 -1e+37 1e+37 0 0 empty empty V\ Ramp 0 -8
0 10 #fcfcfc #000000 #000000 1000 256 3;
#X obj 1309 868 nbx 5 14 -1e+37 1e+37 0 0 empty empty LP\ time 0 -8
0 10 #fcfcfc #000000 #000000 0.01 256 3;
#X obj 1375 747 nbx 5 14 -1e+37 1e+37 0 0 empty empty angP\ gain 0
-8 0 10 #fcfcfc #000000 #000000 20 256 3;
#X obj 1378 779 nbx 5 14 -1e+37 1e+37 0 0 empty empty angP\ lim 0 -8
0 10 #fcfcfc #000000 #000000 20 256 3;
#X obj 1379 836 nbx 5 14 -1e+37 1e+37 0 0 empty empty V\ limit 0 -8
0 10 #fcfcfc #000000 #000000 8 256 3;
#X obj 844 696 hradio 53 0 1 3 empty empty empty 0 -8 0 10 #fcfcfc
#000000 #000000 1;
#X text 778 711 Control;
#X text 837 752 Voltage;
#X text 894 753 Velocity;
#X text 959 754 Position;
#X msg 1118 636 set \$1;
#X msg 1146 637 set \$1;
#X msg 1177 636 set \$1;
#X msg 1205 636 set \$1;
#X msg 1236 636 set \$1;
#X msg 1265 636 set \$1;
#X msg 1294 637 set \$1;
#X msg 1324 637 set \$1;
#X msg 1353 637 set \$1;
#X obj 845 898 s osctargetedout;
#X obj 1325 976 s osctargetedout;
#X obj 1379 936 prepend /M2/L;
#X obj 1372 925 prepend /M2/N;
#X obj 1364 912 prepend /M2/K;
#X obj 1296 947 prepend /M2/F;
#X obj 1291 940 prepend /M2/R;
#X obj 1287 933 prepend /M2/D;
#X obj 1281 925 prepend /M2/I;
#X obj 1276 917 prepend /M2/P;
#X obj 526 947 prepend /M1/F;
#X obj 521 940 prepend /M1/R;
#X obj 517 933 prepend /M1/D;
#X obj 511 925 prepend /M1/I;
#X obj 506 917 prepend /M1/P;
#X obj 393 78 nbx 2 14 0 50 0 1 empty empty empty 0 -8 0 10 #fcfcfc
#000000 #000000 6 256 2;
#X obj 299 71 nbx 5 24 -20 20 0 0 empty empty empty 0 -8 0 10 #fcfcfc
#000000 #000000 -0.266666 256 2;
#X obj 179 74 nbx 7 23 -5000 5000 0 0 empty empty empty 0 -8 0 10 #fcfcfc
#000000 #000000 -84.8824 256 2;
#X obj 577 169 hsl 104 30 -3.1415 3.1415 0 0 empty empty Set\ point\ (Position)
-2 -8 0 10 #fcfcfc #000000 #000000 10300 1;
#X obj 708 68 vsl 31 122 0 12 0 0 empty empty Set\ point\ (Voltage)
0 -9 0 10 #fcfcfc #000000 #000000 0 1;
#X obj 246 13 / 0.10472;
#X msg 318 13 set \$1;
#X obj 457 11 *;
#X obj 384 11 / 6.28319;
#X obj 547 96 /;
#X obj 547 125 * 6.28319;
#X obj 547 66 nbx 5 24 -100 100 0 0 empty empty empty 0 -8 0 10 #fcfcfc
#000000 #000000 0.0599999 256 2;
#X text 534 68 m;
#X obj 20 6 r setpointin;
#X obj 17 36 r setpointin2;
#X obj 120 6 spigot;
#X obj 120 42 spigot;
#X obj 16 63 r motorselect;
#X obj 1339 99 r setpointin;
#X obj 1345 150 r setpointin2;
#X msg 493 11 set \$1;
#X obj 22 103 > 1;
#X obj 59 103 <= 1;
#X msg 1110 529 /M?/params;
#X obj 1110 502 loadbang;
#X msg 1339 126 set \$1;
#X msg 1343 174 set \$1;
#X obj 639 9 *;
#X obj 566 9 / 6.28319;
#X msg 675 9 set \$1;
#X obj 483 448 loadbang;
#X text 284 74 m/s;
#X obj 845 866 prepend /M2/C;
#X msg 163 226 sendtyped /M?/t f 0;
#X obj 458 224 prepend sendtyped /t f;
#X msg 991 301 sendtyped /M2/t f 0;
#X msg 983 274 sendtyped /M1/t f 0;
#X obj 1051 286 prepend sendtyped /M1/t f;
#X obj 1047 322 prepend sendtyped /M2/t f;
#X obj 475 171 nbx 7 21 -1e+37 1e+37 0 0 empty empty rad 0 -8 0 10
#fcfcfc #000000 #000000 2 256 2;
#X connect 1 0 3 0;
#X connect 4 0 1 0;
#X connect 5 0 4 1;
#X connect 6 0 10 0;
#X connect 7 0 2 0;
#X connect 8 0 7 1;
#X connect 9 0 7 0;
#X connect 9 0 22 0;
#X connect 11 0 9 0;
#X connect 12 0 18 0;
#X connect 12 0 4 0;
#X connect 13 0 163 0;
#X connect 14 0 164 0;
#X connect 15 0 159 0;
#X connect 16 0 17 0;
#X connect 17 0 131 0;
#X connect 17 0 134 0;
#X connect 17 0 160 0;
#X connect 18 0 10 0;
#X connect 19 0 18 1;
#X connect 20 0 10 0;
#X connect 21 0 12 0;
#X connect 22 0 23 0;
#X connect 22 1 82 0;
#X connect 23 0 26 0;
#X connect 23 1 29 0;
#X connect 23 2 28 0;
#X connect 23 3 27 0;
#X connect 23 4 65 0;
#X connect 23 5 66 0;
#X connect 23 6 67 0;
#X connect 23 7 68 0;
#X connect 23 8 69 0;
#X connect 23 9 70 0;
#X connect 23 10 71 0;
#X connect 23 11 72 0;
#X connect 23 12 73 0;
#X connect 25 0 24 0;
#X connect 28 0 25 0;
#X connect 30 0 125 0;
#X connect 31 0 124 0;
#X connect 32 0 123 0;
#X connect 33 0 122 0;
#X connect 34 0 121 0;
#X connect 35 0 77 0;
#X connect 36 0 78 0;
#X connect 37 0 79 0;
#X connect 38 0 40 0;
#X connect 40 0 41 0;
#X connect 40 1 42 0;
#X connect 40 2 43 0;
#X connect 41 0 12 0;
#X connect 42 0 12 0;
#X connect 43 0 12 0;
#X connect 44 0 18 0;
#X connect 44 0 4 0;
#X connect 45 0 44 0;
#X connect 46 0 12 0;
#X connect 47 0 46 0;
#X connect 53 0 162 0;
#X connect 54 0 161 0;
#X connect 55 0 75 0;
#X connect 60 0 61 0;
#X connect 61 0 17 0;
#X connect 64 0 60 1;
#X connect 64 0 133 1;
#X connect 64 0 135 1;
#X connect 64 0 153 1;
#X connect 65 0 30 0;
#X connect 66 0 31 0;
#X connect 67 0 32 0;
#X connect 68 0 33 0;
#X connect 69 0 34 0;
#X connect 70 0 35 0;
#X connect 71 0 36 0;
#X connect 72 0 37 0;
#X connect 73 0 55 0;
#X connect 75 0 74 0;
#X connect 76 0 45 0;
#X connect 77 0 80 0;
#X connect 78 0 80 0;
#X connect 79 0 80 0;
#X connect 82 0 85 0;
#X connect 82 1 88 0;
#X connect 82 2 87 0;
#X connect 82 3 86 0;
#X connect 82 4 102 0;
#X connect 82 5 103 0;
#X connect 82 6 104 0;
#X connect 82 7 105 0;
#X connect 82 8 106 0;
#X connect 82 9 107 0;
#X connect 82 10 108 0;
#X connect 82 11 109 0;
#X connect 82 12 110 0;
#X connect 84 0 83 0;
#X connect 87 0 84 0;
#X connect 89 0 120 0;
#X connect 90 0 119 0;
#X connect 91 0 118 0;
#X connect 92 0 117 0;
#X connect 93 0 116 0;
#X connect 94 0 115 0;
#X connect 95 0 114 0;
#X connect 96 0 113 0;
#X connect 97 0 158 0;
#X connect 102 0 89 0;
#X connect 103 0 90 0;
#X connect 104 0 91 0;
#X connect 105 0 92 0;
#X connect 106 0 93 0;
#X connect 107 0 94 0;
#X connect 108 0 95 0;
#X connect 109 0 96 0;
#X connect 110 0 97 0;
#X connect 113 0 112 0;
#X connect 114 0 112 0;
#X connect 115 0 112 0;
#X connect 116 0 112 0;
#X connect 117 0 112 0;
#X connect 118 0 112 0;
#X connect 119 0 112 0;
#X connect 120 0 112 0;
#X connect 121 0 80 0;
#X connect 122 0 80 0;
#X connect 123 0 80 0;
#X connect 124 0 80 0;
#X connect 125 0 80 0;
#X connect 126 0 64 0;
#X connect 127 0 60 0;
#X connect 128 0 16 0;
#X connect 129 0 165 0;
#X connect 130 0 160 0;
#X connect 131 0 132 0;
#X connect 132 0 128 0;
#X connect 133 0 146 0;
#X connect 134 0 133 0;
#X connect 135 0 136 0;
#X connect 136 0 165 0;
#X connect 137 0 135 0;
#X connect 139 0 141 0;
#X connect 140 0 142 0;
#X connect 143 0 147 0;
#X connect 143 0 148 0;
#X connect 144 0 151 0;
#X connect 145 0 152 0;
#X connect 146 0 127 0;
#X connect 147 0 142 1;
#X connect 148 0 141 1;
#X connect 149 0 44 0;
#X connect 150 0 149 0;
#X connect 151 0 13 0;
#X connect 152 0 14 0;
#X connect 153 0 155 0;
#X connect 154 0 153 0;
#X connect 155 0 137 0;
#X connect 156 0 20 0;
#X connect 158 0 111 0;
#X connect 159 0 44 0;
#X connect 160 0 21 0;
#X connect 161 0 44 0;
#X connect 162 0 44 0;
#X connect 163 0 45 0;
#X connect 164 0 45 0;
#X connect 165 0 160 0;
#X connect 165 0 154 0;

View File

@@ -0,0 +1,4 @@
#define MYSSID "yourssid"
#define MYPASS "yourpassword"

Binary file not shown.

After

Width:  |  Height:  |  Size: 256 KiB

View File

@@ -0,0 +1,125 @@
#include <Arduino.h>
#include <SimpleFOC.h>
BLDCMotor motor = BLDCMotor(11);
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 10, 11, 8);
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
MagneticSensorI2C sensor = MagneticSensorI2C(0x36, 12, 0X0C, 4);
/**
* This measures how closely sensor and electrical angle agree and how much your motor is affected by 'cogging'.
* It can be used to investigate how much non linearity there is between what we set (electrical angle) and what we read (sensor angle)
* This non linearity could be down to magnet placement, coil winding differences or simply that the magnetic field when travelling through a pole pair is not linear
* An alignment error of ~10 degrees and cogging of ~4 degrees is normal for small gimbal.
* The following article is an interesting read
* https://hackaday.com/2016/02/23/anti-cogging-algorithm-brings-out-the-best-in-your-hobby-brushless-motors/
*/
void testAlignmentAndCogging(int direction) {
motor.move(0);
_delay(200);
sensor.update();
float initialAngle = sensor.getAngle();
const int shaft_rotation = 720; // 720 deg test - useful to see repeating cog pattern
int sample_count = int(shaft_rotation * motor.pole_pairs); // test every electrical degree
float stDevSum = 0;
float mean = 0.0f;
float prev_mean = 0.0f;
for (int i = 0; i < sample_count; i++) {
float shaftAngle = (float) direction * i * shaft_rotation / sample_count;
float electricAngle = (float) shaftAngle * motor.pole_pairs;
// move and wait
motor.move(shaftAngle * PI / 180);
_delay(5);
// measure
sensor.update();
float sensorAngle = (sensor.getAngle() - initialAngle) * 180 / PI;
float sensorElectricAngle = sensorAngle * motor.pole_pairs;
float electricAngleError = electricAngle - sensorElectricAngle;
// plot this - especially electricAngleError
Serial.print(electricAngle);
Serial.print("\t");
Serial.print(sensorElectricAngle );
Serial.print("\t");
Serial.println(electricAngleError);
// use knuth standard deviation algorithm so that we don't need an array too big for an Uno
prev_mean = mean;
mean = mean + (electricAngleError-mean)/(i+1);
stDevSum = stDevSum + (electricAngleError-mean)*(electricAngleError-prev_mean);
}
Serial.println();
Serial.println(F("ALIGNMENT AND COGGING REPORT"));
Serial.println();
Serial.print(F("Direction: "));
Serial.println(direction);
Serial.print(F("Mean error (alignment): "));
Serial.print(mean);
Serial.println(" deg (electrical)");
Serial.print(F("Standard Deviation (cogging): "));
Serial.print(sqrt(stDevSum/sample_count));
Serial.println(F(" deg (electrical)"));
Serial.println();
Serial.println(F("Plotting 3rd column of data (electricAngleError) will likely show sinusoidal cogging pattern with a frequency of 4xpole_pairs per rotation"));
Serial.println();
}
void setup() {
Serial.begin(115200);
while (!Serial) ;
// driver config
driver.voltage_power_supply = 12;
driver.init();
motor.linkDriver(&driver);
motor.voltage_sensor_align = 3;
motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
motor.controller = MotionControlType::angle_openloop;
motor.voltage_limit=motor.voltage_sensor_align;
sensor.init();
motor.linkSensor(&sensor);
motor.useMonitoring(Serial);
motor.init();
motor.initFOC();
testAlignmentAndCogging(1);
motor.move(0);
Serial.println(F("Press any key to test in CCW direction"));
while (!Serial.available()) { }
testAlignmentAndCogging(-1);
Serial.println(F("Complete"));
motor.voltage_limit = 0;
motor.move(0);
while (true) ; //do nothing;
}
void loop() {
}

View File

@@ -0,0 +1,102 @@
/**
*
* Find KV rating for motor with encoder
*
* Motor KV rating is defiend as the increase of the motor velocity expressed in rotations per minute [rpm] per each 1 Volt int voltage control mode.
*
* This example will set your motor in the torque control mode using voltage and set 1 volt to the motor. By reading the velocity it will calculat the motors KV rating.
* - To make this esimation more credible you can try increasing the target voltage (or decrease in some cases)
* - The KV rating should be realatively static number - it should not change considerably with the increase in the voltage
*
*/
#include <SimpleFOC.h>
// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(11);
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
// Stepper motor & driver instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
// encoder instance
Encoder sensor = Encoder(2, 3, 8192);
// Interrupt routine intialisation
// channel A and B callbacks
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
// voltage set point variable
float target_voltage = 1;
// instantiate the commander
Commander command = Commander(Serial);
void doTarget(char* cmd) { command.scalar(&target_voltage, cmd); }
void calcKV(char* cmd) {
// calculate the KV
Serial.println(motor.shaft_velocity/motor.target*30.0f/_PI);
}
void setup() {
// initialize encoder sensor hardware
sensor.init();
sensor.enableInterrupts(doA, doB);
// link the motor to the sensor
motor.linkSensor(&sensor);
// driver config
// IMPORTANT!
// make sure to set the correct power supply voltage [V]
driver.voltage_power_supply = 12;
driver.init();
// link driver
motor.linkDriver(&driver);
// aligning voltage
motor.voltage_sensor_align = 3;
// set motion control loop to be used
motor.controller = MotionControlType::torque;
// 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");
command.add('K', calcKV, "calculate KV rating");
Serial.println(F("Motor ready."));
Serial.println(F("Set the target voltage : - commnad T"));
Serial.println(F("Calculate the motor KV : - command K"));
_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();
}

View File

@@ -0,0 +1,99 @@
/**
*
* Find KV rating for motor with Hall sensors
*
* Motor KV rating is defiend as the increase of the motor velocity expressed in rotations per minute [rpm] per each 1 Volt int voltage control mode.
*
* This example will set your motor in the torque control mode using voltage and set 1 volt to the motor. By reading the velocity it will calculat the motors KV rating.
* - To make this esimation more credible you can try increasing the target voltage (or decrease in some cases)
* - The KV rating should be realatively static number - it should not change considerably with the increase in the voltage
*/
#include <SimpleFOC.h>
// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(11);
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
// hall sensor instance
HallSensor sensor = HallSensor(2, 3, 4, 11);
// Interrupt routine intialisation
// channel A and B callbacks
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
void doC(){sensor.handleC();}
// voltage set point variable
float target_voltage = 1;
// instantiate the commander
Commander command = Commander(Serial);
void doTarget(char* cmd) { command.scalar(&target_voltage, cmd); }
void calcKV(char* cmd) {
// calculate the KV
Serial.println(motor.shaft_velocity/motor.target*30.0f/_PI);
}
void setup() {
// initialize encoder sensor hardware
sensor.init();
sensor.enableInterrupts(doA, doB, doC);
// link the motor to the sensor
motor.linkSensor(&sensor);
// driver config
// IMPORTANT!
// make sure to set the correct power supply voltage [V]
driver.voltage_power_supply = 12;
driver.init();
// link driver
motor.linkDriver(&driver);
// aligning voltage
motor.voltage_sensor_align = 3;
// set motion control loop to be used
motor.controller = MotionControlType::torque;
// 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");
command.add('K', calcKV, "calculate KV rating");
Serial.println(F("Motor ready."));
Serial.println(F("Set the target voltage : - commnad T"));
Serial.println(F("Calculate the motor KV : - command K"));
_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();
}

View File

@@ -0,0 +1,96 @@
/**
* Find KV rating for motor with magnetic sensors
*
* Motor KV rating is defiend as the increase of the motor velocity expressed in rotations per minute [rpm] per each 1 Volt int voltage control mode.
*
* This example will set your motor in the torque control mode using voltage and set 1 volt to the motor. By reading the velocity it will calculat the motors KV rating.
* - To make this esimation more credible you can try increasing the target voltage (or decrease in some cases)
* - The KV rating should be realatively static number - it should not change considerably with the increase in the voltage
*/
#include <SimpleFOC.h>
// magnetic sensor instance - SPI
MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, 10);
// magnetic sensor instance - I2C
// MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);
// magnetic sensor instance - analog output
// MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020);
// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(11);
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
// Stepper motor & driver instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
// voltage set point variable
float target_voltage = 1;
// instantiate the commander
Commander command = Commander(Serial);
void doTarget(char* cmd) { command.scalar(&target_voltage, cmd); }
void calcKV(char* cmd) {
// calculate the KV
Serial.println(motor.shaft_velocity/motor.target*30.0f/_PI);
}
void setup() {
// initialize encoder sensor hardware
sensor.init();
// link the motor to the sensor
motor.linkSensor(&sensor);
// driver config
// IMPORTANT!
// make sure to set the correct power supply voltage [V]
driver.voltage_power_supply = 12;
driver.init();
// link driver
motor.linkDriver(&driver);
// aligning voltage
motor.voltage_sensor_align = 3;
// set motion control loop to be used
motor.controller = MotionControlType::torque;
// 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");
command.add('K', calcKV, "calculate KV rating");
Serial.println(F("Motor ready."));
Serial.println(F("Set the target voltage : - commnad T"));
Serial.println(F("Calculate the motor KV : - command K"));
_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();
}

View File

@@ -0,0 +1,173 @@
/**
* Utility arduino sketch which finds pole pair number of the motor
*
* To run it just set the correct pin numbers for the BLDC driver and encoder A and B channel as well as the encoder PPR value.
*
* The program will rotate your motor a specific amount and check how much it moved, and by doing a simple calculation calculate your pole pair number.
* The pole pair number will be outputted to the serial terminal.
*
* If the pole pair number is well estimated your motor will start to spin in voltage mode with 2V target.
*
* If the code calculates negative pole pair number please invert your encoder A and B channel pins or motor connector.
*
* Try running this code several times to avoid statistical errors.
* > But in general if your motor spins, you have a good pole pairs number.
*/
#include <SimpleFOC.h>
// BLDC motor instance
// its important to put pole pairs number as 1!!!
BLDCMotor motor = BLDCMotor(1);
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
// Stepper motor instance
// its important to put pole pairs number as 1!!!
//StepperMotor motor = StepperMotor(1);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
// Encoder(int encA, int encB , int cpr, int index)
Encoder encoder = Encoder(2, 3, 2048);
// interrupt routine intialisation
void doA(){encoder.handleA();}
void doB(){encoder.handleB();}
void setup() {
// initialise encoder hardware
encoder.init();
// hardware interrupt enable
encoder.enableInterrupts(doA, doB);
// link the motor to the sensor
motor.linkSensor(&encoder);
// power supply voltage
// default 12V
driver.voltage_power_supply = 12;
driver.init();
motor.linkDriver(&driver);
// initialize motor
motor.init();
// monitoring port
Serial.begin(115200);
// pole pairs calculation routine
Serial.println("Pole pairs (PP) estimator");
Serial.println("-\n");
float pp_search_voltage = 4; // maximum power_supply_voltage/2
float pp_search_angle = 6*_PI; // search electrical angle to turn
// move motor to the electrical angle 0
motor.controller = MotionControlType::angle_openloop;
motor.voltage_limit=pp_search_voltage;
motor.move(0);
_delay(1000);
// read the encoder angle
encoder.update();
float angle_begin = encoder.getAngle();
_delay(50);
// move the motor slowly to the electrical angle pp_search_angle
float motor_angle = 0;
while(motor_angle <= pp_search_angle){
motor_angle += 0.01f;
motor.move(motor_angle);
_delay(1);
}
_delay(1000);
// read the encoder value for 180
encoder.update();
float angle_end = encoder.getAngle();
_delay(50);
// turn off the motor
motor.move(0);
_delay(1000);
// calculate the pole pair number
int pp = round((pp_search_angle)/(angle_end-angle_begin));
Serial.print(F("Estimated PP : "));
Serial.println(pp);
Serial.println(F("PP = Electrical angle / Encoder angle "));
Serial.print(pp_search_angle*180/_PI);
Serial.print("/");
Serial.print((angle_end-angle_begin)*180/_PI);
Serial.print(" = ");
Serial.println((pp_search_angle)/(angle_end-angle_begin));
Serial.println();
// a bit of monitoring the result
if(pp <= 0 ){
Serial.println(F("PP number cannot be negative"));
Serial.println(F(" - Try changing the search_voltage value or motor/encoder configuration."));
return;
}else if(pp > 30){
Serial.println(F("PP number very high, possible error."));
}else{
Serial.println(F("If PP is estimated well your motor should turn now!"));
Serial.println(F(" - If it is not moving try to relaunch the program!"));
Serial.println(F(" - You can also try to adjust the target voltage using serial terminal!"));
}
// set FOC loop to be used
motor.controller = MotionControlType::torque;
// set the pole pair number to the motor
motor.pole_pairs = pp;
//align encoder and start FOC
motor.initFOC();
_delay(1000);
Serial.println(F("\n Motor ready."));
Serial.println(F("Set the target voltage using serial terminal:"));
}
// uq voltage
float target_voltage = 2;
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);
// communicate with the user
serialReceiveUserCommand();
}
// utility function enabling serial communication with the user to set the target values
// this function can be implemented in serialEvent function as well
void serialReceiveUserCommand() {
// a string to hold incoming data
static String received_chars;
while (Serial.available()) {
// get the new byte:
char inChar = (char)Serial.read();
// add it to the string buffer:
received_chars += inChar;
// end of user input
if (inChar == '\n') {
// change the motor target
target_voltage = received_chars.toFloat();
Serial.print("Target voltage: ");
Serial.println(target_voltage);
// reset the command buffer
received_chars = "";
}
}
}

View File

@@ -0,0 +1,173 @@
/**
* Utility arduino sketch which finds pole pair number of the motor
*
* To run it just set the correct pin numbers for the BLDC driver and sensor CPR value and chip select pin.
*
* The program will rotate your motor a specific amount and check how much it moved, and by doing a simple calculation calculate your pole pair number.
* The pole pair number will be outputted to the serial terminal.
*
* If the pole pair number is well estimated your motor will start to spin in voltage mode with 2V target.
*
* If the code calculates negative pole pair number please invert your motor connector.
*
* Try running this code several times to avoid statistical errors.
* > But in general if your motor spins, you have a good pole pairs number.
*/
#include <SimpleFOC.h>
// BLDC motor instance
// its important to put pole pairs number as 1!!!
BLDCMotor motor = BLDCMotor(1);
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
// Stepper motor instance
// its important to put pole pairs number as 1!!!
//StepperMotor motor = StepperMotor(1);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
// magnetic sensor instance - SPI
MagneticSensorSPI sensor = MagneticSensorSPI(10, 14, 0x3FFF);
// magnetic sensor instance - I2C
//MagneticSensorI2C sensor = MagneticSensorI2C(0x36, 12, 0X0C, 4);
// magnetic sensor instance - analog output
// MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020);
void setup() {
// initialise magnetic sensor hardware
sensor.init();
// link the motor to the sensor
motor.linkSensor(&sensor);
// power supply voltage
// default 12V
driver.voltage_power_supply = 12;
driver.init();
motor.linkDriver(&driver);
// initialize motor hardware
motor.init();
// monitoring port
Serial.begin(115200);
// pole pairs calculation routine
Serial.println("Pole pairs (PP) estimator");
Serial.println("-\n");
float pp_search_voltage = 4; // maximum power_supply_voltage/2
float pp_search_angle = 6*_PI; // search electrical angle to turn
// move motor to the electrical angle 0
motor.controller = MotionControlType::angle_openloop;
motor.voltage_limit=pp_search_voltage;
motor.move(0);
_delay(1000);
// read the sensor angle
sensor.update();
float angle_begin = sensor.getAngle();
_delay(50);
// move the motor slowly to the electrical angle pp_search_angle
float motor_angle = 0;
while(motor_angle <= pp_search_angle){
motor_angle += 0.01f;
sensor.update(); // keep track of the overflow
motor.move(motor_angle);
_delay(1);
}
_delay(1000);
// read the sensor value for 180
sensor.update();
float angle_end = sensor.getAngle();
_delay(50);
// turn off the motor
motor.move(0);
_delay(1000);
// calculate the pole pair number
int pp = round((pp_search_angle)/(angle_end-angle_begin));
Serial.print(F("Estimated PP : "));
Serial.println(pp);
Serial.println(F("PP = Electrical angle / Encoder angle "));
Serial.print(pp_search_angle*180/_PI);
Serial.print(F("/"));
Serial.print((angle_end-angle_begin)*180/_PI);
Serial.print(F(" = "));
Serial.println((pp_search_angle)/(angle_end-angle_begin));
Serial.println();
// a bit of monitoring the result
if(pp <= 0 ){
Serial.println(F("PP number cannot be negative"));
Serial.println(F(" - Try changing the search_voltage value or motor/sensor configuration."));
return;
}else if(pp > 30){
Serial.println(F("PP number very high, possible error."));
}else{
Serial.println(F("If PP is estimated well your motor should turn now!"));
Serial.println(F(" - If it is not moving try to relaunch the program!"));
Serial.println(F(" - You can also try to adjust the target voltage using serial terminal!"));
}
// set motion control loop to be used
motor.controller = MotionControlType::torque;
// set the pole pair number to the motor
motor.pole_pairs = pp;
//align sensor and start FOC
motor.initFOC();
_delay(1000);
Serial.println(F("\n Motor ready."));
Serial.println(F("Set the target voltage using serial terminal:"));
}
// uq voltage
float target_voltage = 2;
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);
// communicate with the user
serialReceiveUserCommand();
}
// utility function enabling serial communication with the user to set the target values
// this function can be implemented in serialEvent function as well
void serialReceiveUserCommand() {
// a string to hold incoming data
static String received_chars;
while (Serial.available()) {
// get the new byte:
char inChar = (char)Serial.read();
// add it to the string buffer:
received_chars += inChar;
// end of user input
if (inChar == '\n') {
// change the motor target
target_voltage = received_chars.toFloat();
Serial.print("Target voltage: ");
Serial.println(target_voltage);
// reset the command buffer
received_chars = "";
}
}
}

View File

@@ -0,0 +1,84 @@
/**
* Simple example intended to help users find the zero offset and natural direction of the sensor.
*
* These values can further be used to avoid motor and sensor alignment procedure.
* To use these values add them to the code:");
* motor.sensor_direction=Direction::CW; // or Direction::CCW
* motor.zero_electric_angle=1.2345; // use the real value!
*
* This will only work for abosolute value sensors - magnetic sensors.
* Bypassing the alignment procedure is not possible for the encoders and for the current implementation of the Hall sensors.
* library version 1.4.2.
*
*/
#include <SimpleFOC.h>
// magnetic sensor instance - SPI
//MagneticSensorSPI sensor = MagneticSensorSPI(10, 14, 0x3FFF);
// magnetic sensor instance - I2C
//MagneticSensorI2C sensor = MagneticSensorI2C(0x36, 12, 0X0C, 4);
// magnetic sensor instance - analog output
MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020);
// BLDC motor instance
BLDCMotor motor = BLDCMotor(11);
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
// Stepper motor instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 5, 10, 6, 8);
void setup() {
// power supply voltage
driver.voltage_power_supply = 12;
driver.init();
motor.linkDriver(&driver);
// initialise magnetic sensor hardware
sensor.init();
// link the motor to the sensor
motor.linkSensor(&sensor);
// aligning voltage
motor.voltage_sensor_align = 7;
// set motion control loop to be used
motor.controller = MotionControlType::torque;
// force direction search - because default is CW
motor.sensor_direction = Direction::UNKNOWN;
// initialize motor
motor.init();
// align sensor and start FOC
motor.initFOC();
Serial.begin(115200);
Serial.println("Sensor zero offset is:");
Serial.println(motor.zero_electric_angle, 4);
Serial.println("Sensor natural direction is: ");
Serial.println(motor.sensor_direction == Direction::CW ? "Direction::CW" : "Direction::CCW");
Serial.println("To use these values add them to the code:");
Serial.print(" motor.sensor_direction=");
Serial.print(motor.sensor_direction == Direction::CW ? "Direction::CW" : "Direction::CCW");
Serial.println(";");
Serial.print(" motor.zero_electric_angle=");
Serial.print(motor.zero_electric_angle, 4);
Serial.println(";");
_delay(1000);
Serial.println("If motor is not moving the alignment procedure was not successfull!!");
}
void loop() {
// main FOC algorithm function
motor.loopFOC();
// Motion control function
motor.move(2);
}

View File

@@ -0,0 +1,53 @@
/**
* Simple example of custom commands that have nothing to do with the simple foc library
*/
#include <SimpleFOC.h>
// instantiate the commander
Commander command = Commander(Serial);
// led control function
void doLed(char* cmd){
if(atoi(cmd)) digitalWrite(LED_BUILTIN, HIGH);
else digitalWrite(LED_BUILTIN, LOW);
};
// get analog input
void doAnalog(char* cmd){
if (cmd[0] == '0') Serial.println(analogRead(A0));
else if (cmd[0] == '1') Serial.println(analogRead(A1));
else if (cmd[0] == '2') Serial.println(analogRead(A2));
else if (cmd[0] == '3') Serial.println(analogRead(A3));
else if (cmd[0] == '4') Serial.println(analogRead(A4));
};
void setup() {
// define pins
pinMode(LED_BUILTIN, OUTPUT);
pinMode(A0, INPUT);
pinMode(A1, INPUT);
pinMode(A2, INPUT);
pinMode(A3, INPUT);
pinMode(A4, INPUT);
// Serial port to be used
Serial.begin(115200);
// add new commands
command.add('L', doLed, "led on/off");
command.add('A', doAnalog, "analog read A0-A4");
Serial.println(F("Commander listening"));
Serial.println(F(" - Send ? to see the node list..."));
Serial.println(F(" - Send L0 to turn the led off and L1 to turn it off"));
Serial.println(F(" - Send A0-A4 to read the analog pins"));
_delay(1000);
}
void loop() {
// user communication
command.run();
_delay(10);
}

View File

@@ -0,0 +1,51 @@
/**
* Simple example of how to use the commander without serial - using just strings
*/
#include <SimpleFOC.h>
// instantiate the commander
Commander command = Commander();
// led control function
void doLed(char* cmd){
if(atoi(cmd)) digitalWrite(LED_BUILTIN, HIGH);
else digitalWrite(LED_BUILTIN, LOW);
};
// get analog input
void doAnalog(char* cmd){
if (cmd[0] == '0') Serial.println(analogRead(A0));
else if (cmd[0] == '1') Serial.println(analogRead(A1));
};
void setup() {
// define pins
pinMode(LED_BUILTIN, OUTPUT);
pinMode(A0, INPUT);
pinMode(A1, INPUT);
// Serial port to be used
Serial.begin(115200);
// add new commands
command.add('L', doLed, "led control");
command.add('A', doAnalog, "analog read A0-A1");
Serial.println(F("Commander running"));
_delay(1000);
}
void loop() {
// user communication
command.run("?");
_delay(2000);
command.run("L0");
_delay(1000);
command.run("A0");
_delay(1000);
command.run("A1");
_delay(1000);
command.run("L1");
_delay(1000);
}

View File

@@ -0,0 +1,79 @@
/**
* A simple example to show how to use the commander with the control loops outside of the scope of the SimpleFOC library
*/
#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(); }
// target voltage to be set to the motor
float target_velocity = 0;
// PID controllers and low pass filters
PIDController PIDv{0.05, 1, 0, 100000000, 12};
LowPassFilter LPFv{0.01};
//add communication
Commander command = Commander(Serial);
void doController(char* cmd) { command.pid(&PIDv, cmd); }
void doFilter(char* cmd) { command.lpf(&LPFv, cmd); }
void doTarget(char* cmd) { command.scalar(&target_velocity, 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.init();
// link driver
motor.linkDriver(&driver);
// set motion control loop to be used ( doing nothing )
motor.torque_controller = TorqueControlType::voltage;
motor.controller = MotionControlType::torque;
// use monitoring with serial
Serial.begin(115200);
motor.useMonitoring(Serial);
// initialize motor
motor.init();
// align sensor and start FOC
motor.initFOC();
// subscribe the new commands
command.add('C', doController, "tune velocity pid");
command.add('F', doFilter, "tune velocity LPF");
command.add('T', doTarget, "motor target");
_delay(1000);
Serial.println(F("Commander listening"));
Serial.println(F(" - Send ? to see the node list..."));
}
void loop() {
// looping foc
motor.loopFOC();
// calculate voltage
float target_voltage = PIDv(target_velocity - LPFv(motor.shaft_velocity));
// set the voltage
motor.move(target_voltage);
// user communication
command.run();
}

View File

@@ -0,0 +1,36 @@
/**
* A simple example of reading step/dir communication
* - this example uses hadware interrupts
*/
#include <SimpleFOC.h>
// angle
float received_angle = 0;
// StepDirListener( step_pin, dir_pin, counter_to_value)
StepDirListener step_dir = StepDirListener(2, 3, 360.0/200.0); // receive the angle in degrees
void onStep() { step_dir.handle(); }
void setup() {
Serial.begin(115200);
// init step and dir pins
step_dir.init();
// enable interrupts
step_dir.enableInterrupt(onStep);
// attach the variable to be updated on each step (optional)
// the same can be done asynchronously by caling step_dir.getValue();
step_dir.attach(&received_angle);
Serial.println(F("Step/Dir listenning."));
_delay(1000);
}
void loop() {
Serial.print(received_angle);
Serial.print("\t");
Serial.println(step_dir.getValue());
_delay(500);
}

View File

@@ -0,0 +1,44 @@
/**
* A simple example of reading step/dir communication
* - this example uses software interrupts - this code is intended primarily
* for Arduino UNO/Mega and similar boards with very limited number of interrupt pins
*/
#include <SimpleFOC.h>
// software interrupt library
#include <PciManager.h>
#include <PciListenerImp.h>
// angle
float received_angle = 0;
// StepDirListener( step_pin, dir_pin, counter_to_value)
StepDirListener step_dir = StepDirListener(4, 5, 2.0f*_PI/200.0); // receive the angle in radians
void onStep() { step_dir.handle(); }
// If no available hadware interrupt pins use the software interrupt
PciListenerImp listenStep(step_dir.pin_step, onStep);
void setup() {
Serial.begin(115200);
// init step and dir pins
step_dir.init();
// enable software interrupts
PciManager.registerListener(&listenStep);
// attach the variable to be updated on each step (optional)
// the same can be done asynchronously by caling step_dir.getValue();
step_dir.attach(&received_angle);
Serial.println(F("Step/Dir listenning."));
_delay(1000);
}
void loop() {
Serial.print(received_angle);
Serial.print("\t");
Serial.println(step_dir.getValue());
_delay(500);
}

View File

@@ -0,0 +1,98 @@
/**
* A position control example using step/dir interface to update the motor position
*/
#include <SimpleFOC.h>
// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(11);
BLDCDriver3PWM driver = BLDCDriver3PWM(10, 5, 6, 8);
// Stepper motor & driver instance
//StepperMotor motor = StepperMotor(50);
//StepperDriver4PWM driver = StepperDriver4PWM(9, 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(); }
// StepDirListener( step_pin, dir_pin, counter_to_value)
StepDirListener step_dir = StepDirListener(A4, A5, 2.0f*_PI/200.0);
void onStep() { step_dir.handle(); }
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::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 = 12;
// 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 = 10;
// maximal velocity of the position control
motor.velocity_limit = 100;
// 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();
// init step and dir pins
step_dir.init();
// enable interrupts
step_dir.enableInterrupt(onStep);
// attach the variable to be updated on each step (optional)
// the same can be done asynchronously by caling motor.move(step_dir.getValue());
step_dir.attach(&motor.target);
Serial.println(F("Motor ready."));
Serial.println(F("Listening to step/dir commands!"));
_delay(1000);
}
void loop() {
// main FOC algorithm function
motor.loopFOC();
// Motion control function
motor.move();
}

View File

@@ -0,0 +1,59 @@
/**
* An example code for the generic current sensing implementation
*/
#include <SimpleFOC.h>
// user defined function for reading the phase currents
// returning the value per phase in amps
PhaseCurrent_s readCurrentSense(){
PhaseCurrent_s c;
// dummy example only reading analog pins
c.a = analogRead(A0);
c.b = analogRead(A1);
c.c = analogRead(A2); // if no 3rd current sense set it to 0
return(c);
}
// user defined function for intialising the current sense
// it is optional and if provided it will be called in current_sense.init()
void initCurrentSense(){
pinMode(A0,INPUT);
pinMode(A1,INPUT);
pinMode(A2,INPUT);
}
// GenericCurrentSense class constructor
// it receives the user defined callback for reading the current sense
// and optionally the user defined callback for current sense initialisation
GenericCurrentSense current_sense = GenericCurrentSense(readCurrentSense, initCurrentSense);
void setup() {
// if callbacks are not provided in the constructor
// they can be assigned directly:
//current_sense.readCallback = readCurrentSense;
//current_sense.initCallback = initCurrentSense;
// initialise the current sensing
current_sense.init();
Serial.begin(115200);
Serial.println("Current sense ready.");
}
void loop() {
PhaseCurrent_s currents = current_sense.getPhaseCurrents();
float current_magnitude = current_sense.getDCCurrent();
Serial.print(currents.a); // milli Amps
Serial.print("\t");
Serial.print(currents.b); // milli Amps
Serial.print("\t");
Serial.print(currents.c); // milli Amps
Serial.print("\t");
Serial.println(current_magnitude); // milli Amps
}

View File

@@ -0,0 +1,36 @@
/**
* Testing example code for the Inline current sensing class
*/
#include <SimpleFOC.h>
// current sensor
// shunt resistor value
// gain value
// pins phase A,B, (C optional)
InlineCurrentSense current_sense = InlineCurrentSense(0.01f, 50.0f, A0, A2);
void setup() {
// initialise the current sensing
current_sense.init();
// for SimpleFOCShield v2.01/v2.0.2
current_sense.gain_b *= -1;
Serial.begin(115200);
Serial.println("Current sense ready.");
}
void loop() {
PhaseCurrent_s currents = current_sense.getPhaseCurrents();
float current_magnitude = current_sense.getDCCurrent();
Serial.print(currents.a*1000); // milli Amps
Serial.print("\t");
Serial.print(currents.b*1000); // milli Amps
Serial.print("\t");
Serial.print(currents.c*1000); // milli Amps
Serial.print("\t");
Serial.println(current_magnitude*1000); // milli Amps
}

View File

@@ -0,0 +1,34 @@
// BLDC driver standalone example
#include <SimpleFOC.h>
// BLDC driver instance
BLDCDriver3PWM driver = BLDCDriver3PWM(9, 5, 6, 8);
void setup() {
// pwm frequency to be used [Hz]
// for atmega328 fixed to 32kHz
// esp32/stm32/teensy configurable
driver.pwm_frequency = 50000;
// 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);
}

View File

@@ -0,0 +1,35 @@
// BLDC driver standalone example
#include <SimpleFOC.h>
// BLDC driver instance
BLDCDriver6PWM driver = BLDCDriver6PWM(5, 6, 9,10, 3, 11, 8);
void setup() {
// pwm frequency to be used [Hz]
// for atmega328 fixed to 32kHz
// esp32/stm32/teensy configurable
driver.pwm_frequency = 50000;
// power supply voltage [V]
driver.voltage_power_supply = 12;
// Max DC voltage allowed - default voltage_power_supply
driver.voltage_limit = 12;
// daad_zone [0,1] - default 0.02f - 2%
driver.dead_zone = 0.05f;
// 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);
}

View File

@@ -0,0 +1,39 @@
// Stepper driver standalone example
#include <SimpleFOC.h>
// Stepper driver instance
// StepperDriver2PWM(pwm1, in1, pwm2, in2, (en1, en2 optional))
int in1[] = {4,5};
int in2[] = {9,8};
StepperDriver2PWM driver = StepperDriver2PWM(3, in1, 10 , in2, 11, 12);
// StepperDriver2PWM(pwm1, dir1, pwm2, dir2,(en1, en2 optional))
// StepperDriver2PWM driver = StepperDriver2PWM(3, 4, 5, 6, 11, 12);
void setup() {
// pwm frequency to be used [Hz]
// for atmega328 fixed to 32kHz
// esp32/stm32/teensy configurable
driver.pwm_frequency = 30000;
// 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
driver.setPwm(3,6);
}

View File

@@ -0,0 +1,34 @@
// Stepper driver standalone example
#include <SimpleFOC.h>
// Stepper driver instance
// StepperDriver4PWM(ph1A, ph1B, ph2A, ph2B, (en1, en2 optional))
StepperDriver4PWM driver = StepperDriver4PWM(5, 6, 9,10, 7, 8);
void setup() {
// pwm frequency to be used [Hz]
// for atmega328 fixed to 32kHz
// esp32/stm32/teensy configurable
driver.pwm_frequency = 30000;
// 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
driver.setPwm(3,6);
}

View File

@@ -0,0 +1,44 @@
/**
* Encoder example code
*
* This is a code intended to test the encoder connections and to demonstrate the encoder setup.
*
*/
#include <SimpleFOC.h>
Encoder encoder = Encoder(2, 3, 8192);
// interrupt routine intialisation
void doA(){encoder.handleA();}
void doB(){encoder.handleB();}
void setup() {
// monitoring port
Serial.begin(115200);
// enable/disable quadrature mode
encoder.quadrature = Quadrature::ON;
// check if you need internal pullups
encoder.pullup = Pullup::USE_EXTERN;
// initialise encoder hardware
encoder.init();
// hardware interrupt enable
encoder.enableInterrupts(doA, doB);
Serial.println("Encoder ready");
_delay(1000);
}
void loop() {
// iterative function updating the sensor internal variables
// it is usually called in motor.loopFOC()
// not doing much for the encoder though
encoder.update();
// display the angle and the angular velocity to the terminal
Serial.print(encoder.getAngle());
Serial.print("\t");
Serial.println(encoder.getVelocity());
}

View File

@@ -0,0 +1,57 @@
/**
* Encoder example code using only software interrupts
*
* This is a code intended to test the encoder connections and to
* demonstrate the encoder setup fully using software interrupts.
* - We use PciManager library: https://github.com/prampec/arduino-pcimanager
*
* This code will work on Arduino devices but not on STM32 devices
*
*/
#include <SimpleFOC.h>
// software interrupt library
#include <PciManager.h>
#include <PciListenerImp.h>
// encoder instance
Encoder encoder = Encoder(A0, A1, 2048);
// interrupt routine intialisation
void doA(){encoder.handleA();}
void doB(){encoder.handleB();}
// encoder interrupt init
PciListenerImp listenerA(encoder.pinA, doA);
PciListenerImp listenerB(encoder.pinB, doB);
void setup() {
// monitoring port
Serial.begin(115200);
// enable/disable quadrature mode
encoder.quadrature = Quadrature::ON;
// check if you need internal pullups
encoder.pullup = Pullup::USE_EXTERN;
// initialise encoder hardware
encoder.init();
// interrupt initialization
PciManager.registerListener(&listenerA);
PciManager.registerListener(&listenerB);
Serial.println("Encoder ready");
_delay(1000);
}
void loop() {
// iterative function updating the sensor internal variables
// it is usually called in motor.loopFOC()
// not doing much for the encoder though
encoder.update();
// display the angle and the angular velocity to the terminal
Serial.print(encoder.getAngle());
Serial.print("\t");
Serial.println(encoder.getVelocity());
}

View File

@@ -0,0 +1,51 @@
/**
* Generic sensor example code
*
* This is a code intended to demonstrate how to implement the generic sensor class
*
*/
#include <SimpleFOC.h>
// sensor reading function example
// for the magnetic sensor with analog communication
// returning an angle in radians in between 0 and 2PI
float readSensor(){
return analogRead(A0)*_2PI/1024.0;
}
// sensor intialising function
void initSensor(){
pinMode(A0,INPUT);
}
// generic sensor class contructor
// - read sensor callback
// - init sensor callback (optional)
GenericSensor sensor = GenericSensor(readSensor, initSensor);
void setup() {
// monitoring port
Serial.begin(115200);
// if callbacks are not provided in the constructor
// they can be assigned directly:
//sensor.readCallback = readSensor;
//sensor.initCallback = initSensor;
sensor.init();
Serial.println("Sensor ready");
_delay(1000);
}
void loop() {
// iterative function updating the sensor internal variables
// it is usually called in motor.loopFOC()
sensor.update();
// display the angle and the angular velocity to the terminal
Serial.print(sensor.getAngle());
Serial.print("\t");
Serial.println(sensor.getVelocity());
}

View File

@@ -0,0 +1,48 @@
/**
* Hall sensor example code
*
* This is a code intended to test the hall sensors connections and to demonstrate the hall sensor setup.
*
*/
#include <SimpleFOC.h>
// Hall sensor instance
// HallSensor(int hallA, int hallB , int cpr, int index)
// - hallA, hallB, hallC - HallSensor A, B and C pins
// - pp - pole pairs
HallSensor sensor = HallSensor(2, 3, 4, 14);
// Interrupt routine intialisation
// channel A and B callbacks
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
void doC(){sensor.handleC();}
void setup() {
// monitoring port
Serial.begin(115200);
// check if you need internal pullups
sensor.pullup = Pullup::USE_EXTERN;
// initialise encoder hardware
sensor.init();
// hardware interrupt enable
sensor.enableInterrupts(doA, doB, doC);
Serial.println("Sensor ready");
_delay(1000);
}
void loop() {
// iterative function updating the sensor internal variables
// it is usually called in motor.loopFOC()
sensor.update();
// display the angle and the angular velocity to the terminal
Serial.print(sensor.getAngle());
Serial.print("\t");
Serial.println(sensor.getVelocity());
delay(100);
}

View File

@@ -0,0 +1,59 @@
/**
* Hall sensors example code using only software interrupts
*
* This is a code intended to test the hall sensor connections and to
* demonstrate the hall sensor setup fully using software interrupts.
* - We use PciManager library: https://github.com/prampec/arduino-pcimanager
*
* This code will work on Arduino devices but not on STM32 devices
*/
#include <SimpleFOC.h>
// software interrupt library
#include <PciManager.h>
#include <PciListenerImp.h>
// Hall sensor instance
// HallSensor(int hallA, int hallB , int cpr, int index)
// - hallA, hallB, hallC - HallSensor A, B and C pins
// - pp - pole pairs
HallSensor sensor = HallSensor(2, 3, 4, 11);
// Interrupt routine intialisation
// channel A and B callbacks
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
void doC(){sensor.handleC();}
// If no available hadware interrupt pins use the software interrupt
PciListenerImp listenA(sensor.pinA, doA);
PciListenerImp listenB(sensor.pinB, doB);
PciListenerImp listenC(sensor.pinC, doC);
void setup() {
// monitoring port
Serial.begin(115200);
// check if you need internal pullups
sensor.pullup = Pullup::USE_EXTERN;
// initialise encoder hardware
sensor.init();
// software interrupts
PciManager.registerListener(&listenA);
PciManager.registerListener(&listenB);
PciManager.registerListener(&listenC);
Serial.println("Sensor ready");
_delay(1000);
}
void loop() {
// iterative function updating the sensor internal variables
// it is usually called in motor.loopFOC()
sensor.update();
// display the angle and the angular velocity to the terminal
Serial.print(sensor.getAngle());
Serial.print("\t");
Serial.println(sensor.getVelocity());
}

View File

@@ -0,0 +1,62 @@
/**
* An example to find the center offsets for both ADC channels used in the LinearHall sensor constructor
* Spin your motor through at least one full revolution to average out all of the variations in magnet strength.
*/
//Change these defines to match the analog input pins that your hall sensors are connected to
#define LINEAR_HALL_CHANNEL_A 39
#define LINEAR_HALL_CHANNEL_B 33
//program variables
int minA, maxA, minB, maxB, centerA, centerB;
unsigned long timestamp;
void setup() {
// monitoring port
Serial.begin(115200);
// initialise magnetic sensor hardware
pinMode(LINEAR_HALL_CHANNEL_A, INPUT);
pinMode(LINEAR_HALL_CHANNEL_B, INPUT);
minA = analogRead(LINEAR_HALL_CHANNEL_A);
maxA = minA;
centerA = (minA + maxA) / 2;
minB = analogRead(LINEAR_HALL_CHANNEL_B);
maxB = minB;
centerB = (minB + maxB) / 2;
Serial.println("Sensor ready");
delay(1000);
timestamp = millis();
}
void loop() {
//read sensors and update variables
int tempA = analogRead(LINEAR_HALL_CHANNEL_A);
if (tempA < minA) minA = tempA;
if (tempA > maxA) maxA = tempA;
centerA = (minA + maxA) / 2;
int tempB = analogRead(LINEAR_HALL_CHANNEL_B);
if (tempB < minB) minB = tempB;
if (tempB > maxB) maxB = tempB;
centerB = (minB + maxB) / 2;
if (millis() > timestamp + 100) {
timestamp = millis();
// display the center counts, and max and min count
Serial.print("A:");
Serial.print(centerA);
Serial.print("\t, B:");
Serial.print(centerB);
Serial.print("\t, min A:");
Serial.print(minA);
Serial.print("\t, max A:");
Serial.print(maxA);
Serial.print("\t, min B:");
Serial.print(minB);
Serial.print("\t, max B:");
Serial.println(maxB);
}
}

View File

@@ -0,0 +1,56 @@
#include <SimpleFOC.h>
/**
* An example to find out the raw max and min count to be provided to the constructor
* Spin your motor/sensor/magnet to see what is the maximum output of the sensor and what is the minimum value
* And replace values 14 and 1020 with new values. Once when you replace them make sure there is no jump in the angle reading sensor.getAngle().
* If there is a jump that means you can still find better values.
*/
/**
* Magnetic sensor reading analog voltage on pin A1. This voltage is proportional to rotation position.
* Tested on AS5600 magnetic sensor running in 'analog mode'. Note AS5600 works better in 'i2C mode' (less noise) but only supports one sensor per i2c bus.
*
* MagneticSensorAnalog(uint8_t _pinAnalog, int _min, int _max)
* - pinAnalog - the pin that is reading the pwm from magnetic sensor
* - min_raw_count - the smallest expected reading. Whilst you might expect it to be 0 it is often ~15. Getting this wrong results in a small click once per revolution
* - max_raw_count - the largest value read. whilst you might expect it to be 2^10 = 1023 it is often ~ 1020. Note ESP32 will be closer to 4096 with its 12bit ADC
*/
MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020);
void setup() {
// monitoring port
Serial.begin(115200);
// initialise magnetic sensor hardware
sensor.init();
Serial.println("Sensor ready");
_delay(1000);
}
int max_count = 0;
int min_count = 100000;
void loop() {
// iterative function updating the sensor internal variables
// it is usually called in motor.loopFOC()
// this function reads the sensor hardware and
// has to be called before getAngle nad getVelocity
sensor.update();
// keep track of min and max
if(sensor.raw_count > max_count) max_count = sensor.raw_count;
else if(sensor.raw_count < min_count) min_count = sensor.raw_count;
// display the raw count, and max and min raw count
Serial.print("angle:");
Serial.print(sensor.getAngle());
Serial.print("\t, raw:");
Serial.print(sensor.raw_count);
Serial.print("\t, min:");
Serial.print(min_count);
Serial.print("\t, max:");
Serial.println(max_count);
delay(100);
}

View File

@@ -0,0 +1,37 @@
#include <SimpleFOC.h>
/**
* Magnetic sensor reading analog voltage on pin A1. This voltage is proportional to rotation position.
* Tested on AS5600 magnetic sensor running in 'analog mode'. Note AS5600 works better in 'i2C mode' (less noise) but only supports one sensor per i2c bus.
*
* MagneticSensorAnalog(uint8_t _pinAnalog, int _min, int _max)
* - pinAnalog - the pin that is reading the pwm from magnetic sensor
* - min_raw_count - the smallest expected reading. Whilst you might expect it to be 0 it is often ~15. Getting this wrong results in a small click once per revolution
* - max_raw_count - the largest value read. whilst you might expect it to be 2^10 = 1023 it is often ~ 1020. Note ESP32 will be closer to 4096 with its 12bit ADC
*/
MagneticSensorAnalog sensor = MagneticSensorAnalog(A1, 14, 1020);
void setup() {
// monitoring port
Serial.begin(115200);
// initialise magnetic sensor hardware
sensor.init();
Serial.println("Sensor ready");
_delay(1000);
}
void loop() {
// iterative function updating the sensor internal variables
// it is usually called in motor.loopFOC()
// this function reads the sensor hardware and
// has to be called before getAngle nad getVelocity
sensor.update();
// display the angle and the angular velocity to the terminal
Serial.print(sensor.getAngle());
Serial.print("\t");
Serial.println(sensor.getVelocity());
}

View File

@@ -0,0 +1,40 @@
#include <SimpleFOC.h>
/** Annoyingly some i2c sensors (e.g. AS5600) have a fixed chip address. This means only one of these devices can be addressed on a single bus
* This example shows how a second i2c bus can be used to communicate with a second sensor.
*/
MagneticSensorI2C sensor0 = MagneticSensorI2C(AS5600_I2C);
MagneticSensorI2C sensor1 = MagneticSensorI2C(AS5600_I2C);
void setup() {
Serial.begin(115200);
_delay(750);
Wire.setClock(400000);
Wire1.setClock(400000);
// Normally SimpleFOC will call begin for i2c but with esp32 begin() is the only way to set pins!
// It seems safe to call begin multiple times
Wire1.begin(19, 23, (uint32_t)400000);
sensor0.init();
sensor1.init(&Wire1);
}
void loop() {
// iterative function updating the sensor internal variables
// it is usually called in motor.loopFOC()
// this function reads the sensor hardware and
// has to be called before getAngle nad getVelocity
sensor0.update();
sensor1.update();
_delay(200);
Serial.print(sensor0.getAngle());
Serial.print(" - ");
Serial.print(sensor1.getAngle());
Serial.println();
}

View File

@@ -0,0 +1,39 @@
#include <SimpleFOC.h>
/** Annoyingly some i2c sensors (e.g. AS5600) have a fixed chip address. This means only one of these devices can be addressed on a single bus
* This example shows how a second i2c bus can be used to communicate with a second sensor.
*/
MagneticSensorI2C sensor0 = MagneticSensorI2C(AS5600_I2C);
MagneticSensorI2C sensor1 = MagneticSensorI2C(AS5600_I2C);
// example of stm32 defining 2nd bus
TwoWire Wire1(PB11, PB10);
void setup() {
Serial.begin(115200);
_delay(750);
Wire.setClock(400000);
Wire1.setClock(400000);
sensor0.init();
sensor1.init(&Wire1);
}
void loop() {
// iterative function updating the sensor internal variables
// it is usually called in motor.loopFOC()
// this function reads the sensor hardware and
// has to be called before getAngle nad getVelocity
sensor0.update();
sensor1.update();
_delay(200);
Serial.print(sensor0.getAngle());
Serial.print(" - ");
Serial.print(sensor1.getAngle());
Serial.println();
}

View File

@@ -0,0 +1,43 @@
#include <SimpleFOC.h>
// MagneticSensorI2C(uint8_t _chip_address, float _cpr, uint8_t _angle_register_msb)
// chip_address I2C chip address
// bit_resolution resolution of the sensor
// angle_register_msb angle read register msb
// bits_used_msb number of used bits in msb register
//
// make sure to read the chip address and the chip angle register msb value from the datasheet
// also in most cases you will need external pull-ups on SDA and SCL lines!!!!!
//
// For AS5058B
// MagneticSensorI2C sensor = MagneticSensorI2C(0x40, 14, 0xFE, 8);
// Example of AS5600 configuration
MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);
void setup() {
// monitoring port
Serial.begin(115200);
// configure i2C
Wire.setClock(400000);
// initialise magnetic sensor hardware
sensor.init();
Serial.println("Sensor ready");
_delay(1000);
}
void loop() {
// iterative function updating the sensor internal variables
// it is usually called in motor.loopFOC()
// this function reads the sensor hardware and
// has to be called before getAngle nad getVelocity
sensor.update();
// display the angle and the angular velocity to the terminal
Serial.print(sensor.getAngle());
Serial.print("\t");
Serial.println(sensor.getVelocity());
}

View File

@@ -0,0 +1,49 @@
#include <SimpleFOC.h>
/**
* An example to find out the raw max and min count to be provided to the constructor
* SPin your motor/sensor/magnet to see what is the maximum output of the sensor and what is the minimum value
* And replace values 4 and 904 with new values. Once when you replace them make sure there is no jump in the angle reading sensor.getAngle().
* If there is a jump that means you can still find better values.
*/
MagneticSensorPWM sensor = MagneticSensorPWM(2, 4, 904);
void doPWM(){sensor.handlePWM();}
void setup() {
// monitoring port
Serial.begin(115200);
// initialise magnetic sensor hardware
sensor.init();
// comment out to use sensor in blocking (non-interrupt) way
sensor.enableInterrupt(doPWM);
Serial.println("Sensor ready");
_delay(1000);
}
int max_pulse= 0;
int min_pulse = 10000;
void loop() {
// iterative function updating the sensor internal variables
// it is usually called in motor.loopFOC()
// this function reads the sensor hardware and
// has to be called before getAngle nad getVelocity
sensor.update();
// keep track of min and max
if(sensor.pulse_length_us > max_pulse) max_pulse = sensor.pulse_length_us;
else if(sensor.pulse_length_us < min_pulse) min_pulse = sensor.pulse_length_us;
// display the raw count, and max and min raw count
Serial.print("angle:");
Serial.print(sensor.getAngle());
Serial.print("\t, raw:");
Serial.print(sensor.pulse_length_us);
Serial.print("\t, min:");
Serial.print(min_pulse);
Serial.print("\t, max:");
Serial.println(max_pulse);
}

View File

@@ -0,0 +1,38 @@
#include <SimpleFOC.h>
/**
* Magnetic sensor reading pwm signal on pin 2. The pwm duty cycle is proportional to the sensor angle.
*
* MagneticSensorPWM(uint8_t MagneticSensorPWM, int _min, int _max)
* - pinPWM - the pin that is reading the pwm from magnetic sensor
* - min_raw_count - the smallest expected reading. Whilst you might expect it to be 0 it is often ~5. Getting this wrong results in a small click once per revolution
* - max_raw_count - the largest value read. whilst you might expect it to be 1kHz = 1000 it is often ~910. depending on the exact frequency and saturation
*/
MagneticSensorPWM sensor = MagneticSensorPWM(2, 4, 904);
void doPWM(){sensor.handlePWM();}
void setup() {
// monitoring port
Serial.begin(115200);
// initialise magnetic sensor hardware
sensor.init();
// comment out to use sensor in blocking (non-interrupt) way
sensor.enableInterrupt(doPWM);
Serial.println("Sensor ready");
_delay(1000);
}
void loop() {
// iterative function updating the sensor internal variables
// it is usually called in motor.loopFOC()
// this function reads the sensor hardware and
// has to be called before getAngle nad getVelocity
sensor.update();
// display the angle and the angular velocity to the terminal
Serial.print(sensor.getAngle());
Serial.print("\t");
Serial.println(sensor.getVelocity());
}

View File

@@ -0,0 +1,44 @@
#include <SimpleFOC.h>
// software interrupt library
#include <PciManager.h>
#include <PciListenerImp.h>
/**
* Magnetic sensor reading analog voltage on pin which does not have hardware interrupt support. Such as A0.
*
* MagneticSensorPWM(uint8_t MagneticSensorPWM, int _min, int _max)
* - pinPWM - the pin that is reading the pwm from magnetic sensor
* - min_raw_count - the smallest expected reading. Whilst you might expect it to be 0 it is often ~5. Getting this wrong results in a small click once per revolution
* - max_raw_count - the largest value read. whilst you might expect it to be 1kHz = 1000 it is often ~910. depending on the exact frequency and saturation
*/
MagneticSensorPWM sensor = MagneticSensorPWM(A0, 4, 904);
void doPWM(){sensor.handlePWM();}
// encoder interrupt init
PciListenerImp listenerPWM(sensor.pinPWM, doPWM);
void setup() {
// monitoring port
Serial.begin(115200);
// initialise magnetic sensor hardware
sensor.init();
// comment out to use sensor in blocking (non-interrupt) way
PciManager.registerListener(&listenerPWM);
Serial.println("Sensor ready");
_delay(1000);
}
void loop() {
// iterative function updating the sensor internal variables
// it is usually called in motor.loopFOC()
// this function reads the sensor hardware and
// has to be called before getAngle nad getVelocity
sensor.update();
// display the angle and the angular velocity to the terminal
Serial.print(sensor.getAngle());
Serial.print("\t");
Serial.println(sensor.getVelocity());
}

View File

@@ -0,0 +1,41 @@
#include <SimpleFOC.h>
// alternative pinout
#define HSPI_MISO 12
#define HSPI_MOSI 13
#define HSPI_SCLK 14
#define HSPI_SS 15
// MagneticSensorSPI(int cs, float _cpr, int _angle_register)
// config - SPI config
// cs - SPI chip select pin
MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, HSPI_SS);
// for esp 32, it has 2 spi interfaces VSPI (default) and HPSI as the second one
// to enable it instatiate the object
SPIClass SPI_2(HSPI);
void setup() {
// monitoring port
Serial.begin(115200);
// start the newly defined spi communication
SPI_2.begin(HSPI_SCLK, HSPI_MISO, HSPI_MOSI, HSPI_SS); //SCLK, MISO, MOSI, SS
// initialise magnetic sensor hardware
sensor.init(&SPI_2);
Serial.println("Sensor ready");
_delay(1000);
}
void loop() {
// iterative function updating the sensor internal variables
// it is usually called in motor.loopFOC()
// this function reads the sensor hardware and
// has to be called before getAngle nad getVelocity
sensor.update();
// display the angle and the angular velocity to the terminal
Serial.print(sensor.getAngle());
Serial.print("\t");
Serial.println(sensor.getVelocity());
}

View File

@@ -0,0 +1,32 @@
#include <SimpleFOC.h>
// MagneticSensorSPI(int cs, float _cpr, int _angle_register)
// config - SPI config
// cs - SPI chip select pin
MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, PA15);
// these are valid pins (mosi, miso, sclk) for 2nd SPI bus on storm32 board (stm32f107rc)
SPIClass SPI_2(PB15, PB14, PB13);
void setup() {
// monitoring port
Serial.begin(115200);
// initialise magnetic sensor hardware
sensor.init(&SPI_2);
Serial.println("Sensor ready");
_delay(1000);
}
void loop() {
// iterative function updating the sensor internal variables
// it is usually called in motor.loopFOC()
// this function reads the sensor hardware and
// has to be called before getAngle nad getVelocity
sensor.update();
// display the angle and the angular velocity to the terminal
Serial.print(sensor.getAngle());
Serial.print("\t");
Serial.println(sensor.getVelocity());
}

View File

@@ -0,0 +1,32 @@
#include <SimpleFOC.h>
// MagneticSensorSPI(MagneticSensorSPIConfig_s config, int cs)
// config - SPI config
// cs - SPI chip select pin
// magnetic sensor instance - SPI
MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, 10);
// alternative constructor (chipselsect, bit_resolution, angle_read_register, )
// MagneticSensorSPI sensor = MagneticSensorSPI(10, 14, 0x3FFF);
void setup() {
// monitoring port
Serial.begin(115200);
// initialise magnetic sensor hardware
sensor.init();
Serial.println("Sensor ready");
_delay(1000);
}
void loop() {
// iterative function updating the sensor internal variables
// it is usually called in motor.loopFOC()
// this function reads the sensor hardware and
// has to be called before getAngle nad getVelocity
sensor.update();
// display the angle and the angular velocity to the terminal
Serial.print(sensor.getAngle());
Serial.print("\t");
Serial.println(sensor.getVelocity());
}