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