try to fix submodule
This commit is contained in:
@@ -0,0 +1,123 @@
|
||||
|
||||
|
||||
|
||||
#include "Arduino.h"
|
||||
#include <Wire.h>
|
||||
#include <SimpleFOC.h>
|
||||
#include <SimpleFOCDrivers.h>
|
||||
#include "drivers/drv8316/drv8316.h"
|
||||
|
||||
|
||||
|
||||
|
||||
BLDCMotor motor = BLDCMotor(11);
|
||||
DRV8316Driver3PWM driver = DRV8316Driver3PWM(2,3,4,7,false); // use the right pins for your setup!
|
||||
#define ENABLE_A 0
|
||||
#define ENABLE_B 1
|
||||
#define ENABLE_C 6
|
||||
|
||||
|
||||
void printDRV8316Status() {
|
||||
DRV8316Status status = driver.getStatus();
|
||||
Serial.println("DRV8316 Status:");
|
||||
Serial.print("Fault: ");
|
||||
Serial.println(status.isFault());
|
||||
Serial.print("Buck Error: ");
|
||||
Serial.print(status.isBuckError());
|
||||
Serial.print(" Undervoltage: ");
|
||||
Serial.print(status.isBuckUnderVoltage());
|
||||
Serial.print(" OverCurrent: ");
|
||||
Serial.println(status.isBuckOverCurrent());
|
||||
Serial.print("Charge Pump UnderVoltage: ");
|
||||
Serial.println(status.isChargePumpUnderVoltage());
|
||||
Serial.print("OTP Error: ");
|
||||
Serial.println(status.isOneTimeProgrammingError());
|
||||
Serial.print("OverCurrent: ");
|
||||
Serial.print(status.isOverCurrent());
|
||||
Serial.print(" Ah: ");
|
||||
Serial.print(status.isOverCurrent_Ah());
|
||||
Serial.print(" Al: ");
|
||||
Serial.print(status.isOverCurrent_Al());
|
||||
Serial.print(" Bh: ");
|
||||
Serial.print(status.isOverCurrent_Bh());
|
||||
Serial.print(" Bl: ");
|
||||
Serial.print(status.isOverCurrent_Bl());
|
||||
Serial.print(" Ch: ");
|
||||
Serial.print(status.isOverCurrent_Ch());
|
||||
Serial.print(" Cl: ");
|
||||
Serial.println(status.isOverCurrent_Cl());
|
||||
Serial.print("OverTemperature: ");
|
||||
Serial.print(status.isOverTemperature());
|
||||
Serial.print(" Shutdown: ");
|
||||
Serial.print(status.isOverTemperatureShutdown());
|
||||
Serial.print(" Warning: ");
|
||||
Serial.println(status.isOverTemperatureWarning());
|
||||
Serial.print("OverVoltage: ");
|
||||
Serial.println(status.isOverVoltage());
|
||||
Serial.print("PowerOnReset: ");
|
||||
Serial.println(status.isPowerOnReset());
|
||||
Serial.print("SPI Error: ");
|
||||
Serial.print(status.isSPIError());
|
||||
Serial.print(" Address: ");
|
||||
Serial.print(status.isSPIAddressError());
|
||||
Serial.print(" Clock: ");
|
||||
Serial.print(status.isSPIClockFramingError());
|
||||
Serial.print(" Parity: ");
|
||||
Serial.println(status.isSPIParityError());
|
||||
if (status.isFault())
|
||||
driver.clearFault();
|
||||
delayMicroseconds(1); // ensure 400ns delay
|
||||
DRV8316_PWMMode val = driver.getPWMMode();
|
||||
Serial.print("PWM Mode: ");
|
||||
Serial.println(val);
|
||||
delayMicroseconds(1); // ensure 400ns delay
|
||||
bool lock = driver.isRegistersLocked();
|
||||
Serial.print("Lock: ");
|
||||
Serial.println(lock);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
void setup() {
|
||||
|
||||
Serial.begin(115200);
|
||||
while (!Serial);
|
||||
delay(1);
|
||||
Serial.println("Initializing...");
|
||||
|
||||
pinMode(ENABLE_A, OUTPUT);
|
||||
digitalWrite(ENABLE_A, 1); // enable
|
||||
pinMode(ENABLE_B, OUTPUT);
|
||||
digitalWrite(ENABLE_B, 1); // enable
|
||||
pinMode(ENABLE_C, OUTPUT);
|
||||
digitalWrite(ENABLE_C, 1); // enable
|
||||
|
||||
driver.voltage_power_supply = 12;
|
||||
driver.init();
|
||||
motor.linkDriver(&driver);
|
||||
motor.controller = MotionControlType::velocity_openloop;
|
||||
motor.voltage_limit = 3;
|
||||
motor.velocity_limit = 20;
|
||||
motor.init();
|
||||
Serial.println("Init complete...");
|
||||
|
||||
delay(100);
|
||||
printDRV8316Status();
|
||||
}
|
||||
|
||||
|
||||
// velocity set point variable
|
||||
float target_velocity = 7.0;
|
||||
|
||||
|
||||
void loop() {
|
||||
//delay(100);
|
||||
//driver.setPwm(7.4/4, 7.4/2, 7.4/4*3);
|
||||
motor.move(target_velocity);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -0,0 +1,111 @@
|
||||
|
||||
|
||||
|
||||
#include "Arduino.h"
|
||||
#include <Wire.h>
|
||||
#include <SimpleFOC.h>
|
||||
#include <SimpleFOCDrivers.h>
|
||||
#include "drivers/drv8316/drv8316.h"
|
||||
|
||||
|
||||
|
||||
|
||||
BLDCMotor motor = BLDCMotor(11);
|
||||
DRV8316Driver6PWM driver = DRV8316Driver6PWM(0,1,2,3,4,6,7,false); // use the right pins for your setup!
|
||||
|
||||
|
||||
|
||||
void printDRV8316Status() {
|
||||
DRV8316Status status = driver.getStatus();
|
||||
Serial.println("DRV8316 Status:");
|
||||
Serial.print("Fault: ");
|
||||
Serial.println(status.isFault());
|
||||
Serial.print("Buck Error: ");
|
||||
Serial.print(status.isBuckError());
|
||||
Serial.print(" Undervoltage: ");
|
||||
Serial.print(status.isBuckUnderVoltage());
|
||||
Serial.print(" OverCurrent: ");
|
||||
Serial.println(status.isBuckOverCurrent());
|
||||
Serial.print("Charge Pump UnderVoltage: ");
|
||||
Serial.println(status.isChargePumpUnderVoltage());
|
||||
Serial.print("OTP Error: ");
|
||||
Serial.println(status.isOneTimeProgrammingError());
|
||||
Serial.print("OverCurrent: ");
|
||||
Serial.print(status.isOverCurrent());
|
||||
Serial.print(" Ah: ");
|
||||
Serial.print(status.isOverCurrent_Ah());
|
||||
Serial.print(" Al: ");
|
||||
Serial.print(status.isOverCurrent_Al());
|
||||
Serial.print(" Bh: ");
|
||||
Serial.print(status.isOverCurrent_Bh());
|
||||
Serial.print(" Bl: ");
|
||||
Serial.print(status.isOverCurrent_Bl());
|
||||
Serial.print(" Ch: ");
|
||||
Serial.print(status.isOverCurrent_Ch());
|
||||
Serial.print(" Cl: ");
|
||||
Serial.println(status.isOverCurrent_Cl());
|
||||
Serial.print("OverTemperature: ");
|
||||
Serial.print(status.isOverTemperature());
|
||||
Serial.print(" Shutdown: ");
|
||||
Serial.print(status.isOverTemperatureShutdown());
|
||||
Serial.print(" Warning: ");
|
||||
Serial.println(status.isOverTemperatureWarning());
|
||||
Serial.print("OverVoltage: ");
|
||||
Serial.println(status.isOverVoltage());
|
||||
Serial.print("PowerOnReset: ");
|
||||
Serial.println(status.isPowerOnReset());
|
||||
Serial.print("SPI Error: ");
|
||||
Serial.print(status.isSPIError());
|
||||
Serial.print(" Address: ");
|
||||
Serial.print(status.isSPIAddressError());
|
||||
Serial.print(" Clock: ");
|
||||
Serial.print(status.isSPIClockFramingError());
|
||||
Serial.print(" Parity: ");
|
||||
Serial.println(status.isSPIParityError());
|
||||
if (status.isFault())
|
||||
driver.clearFault();
|
||||
delayMicroseconds(1); // ensure 400ns delay
|
||||
DRV8316_PWMMode val = driver.getPWMMode();
|
||||
Serial.print("PWM Mode: ");
|
||||
Serial.println(val);
|
||||
delayMicroseconds(1); // ensure 400ns delay
|
||||
bool lock = driver.isRegistersLocked();
|
||||
Serial.print("Lock: ");
|
||||
Serial.println(lock);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
while (!Serial);
|
||||
delay(1);
|
||||
Serial.println("Initializing...");
|
||||
|
||||
driver.voltage_power_supply = 12;
|
||||
driver.init();
|
||||
motor.linkDriver(&driver);
|
||||
motor.controller = MotionControlType::velocity_openloop;
|
||||
motor.voltage_limit = 3;
|
||||
motor.velocity_limit = 20;
|
||||
motor.init();
|
||||
Serial.println("Init complete...");
|
||||
|
||||
delay(100);
|
||||
printDRV8316Status();
|
||||
}
|
||||
|
||||
|
||||
// velocity set point variable
|
||||
float target_velocity = 7.0;
|
||||
|
||||
|
||||
void loop() {
|
||||
motor.move(target_velocity);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -0,0 +1,86 @@
|
||||
/**
|
||||
* 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>
|
||||
#include <SimpleFOCDrivers.h>
|
||||
#include "encoders/calibrated/CalibratedSensor.h"
|
||||
|
||||
// magnetic sensor instance - SPI
|
||||
MagneticSensorSPI sensor = MagneticSensorSPI(AS5048_SPI, PB6);
|
||||
// BLDC motor & driver instance
|
||||
BLDCMotor motor = BLDCMotor(11);
|
||||
BLDCDriver3PWM driver = BLDCDriver3PWM(PB4,PC7,PB10,PA9);
|
||||
// instantiate the calibrated sensor object
|
||||
CalibratedSensor sensor_calibrated = CalibratedSensor(sensor);
|
||||
|
||||
// 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() {
|
||||
|
||||
SPI.setMISO(PB14);
|
||||
SPI.setMOSI(PB15);
|
||||
SPI.setSCLK(PB13);
|
||||
|
||||
sensor.init();
|
||||
// Link motor to sensor
|
||||
motor.linkSensor(&sensor);
|
||||
// power supply voltage
|
||||
driver.voltage_power_supply = 20;
|
||||
driver.init();
|
||||
motor.linkDriver(&driver);
|
||||
// aligning voltage
|
||||
motor.voltage_sensor_align = 8;
|
||||
motor.voltage_limit = 20;
|
||||
// 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);
|
||||
motor.monitor_variables = _MON_VEL;
|
||||
motor.monitor_downsample = 10; // default 10
|
||||
|
||||
// initialize motor
|
||||
motor.init();
|
||||
|
||||
// set voltage to run calibration
|
||||
sensor_calibrated.voltage_calibration = 6;
|
||||
// Running calibration
|
||||
sensor_calibrated.calibrate(motor);
|
||||
|
||||
//Serial.println("Calibrating Sensor Done.");
|
||||
// Linking sensor to motor object
|
||||
motor.linkSensor(&sensor_calibrated);
|
||||
|
||||
// calibrated init 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() {
|
||||
|
||||
motor.loopFOC();
|
||||
motor.move(target_voltage);
|
||||
command.run();
|
||||
motor.monitor();
|
||||
|
||||
}
|
||||
@@ -0,0 +1,106 @@
|
||||
/**
|
||||
* Comprehensive BLDC motor control example using magnetic sensor MT6816
|
||||
*
|
||||
* 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>
|
||||
#include <SimpleFOCDrivers.h>
|
||||
#include <encoders/mt6816/MagneticSensorMT6816.h>
|
||||
|
||||
// magnetic sensor instance - MT6816 SPI mode
|
||||
MagneticSensorMT6816 sensor = MagneticSensorMT6816(5);
|
||||
|
||||
|
||||
// BLDC motor & driver instance
|
||||
BLDCMotor motor = BLDCMotor(7);
|
||||
BLDCDriver3PWM driver = BLDCDriver3PWM(32, 25, 26, 33);
|
||||
|
||||
// Inline Current Sense instance
|
||||
InlineCurrentSense current_sense = InlineCurrentSense(0.01f, 50.0f, 35, 34);
|
||||
|
||||
// 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 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);
|
||||
|
||||
current_sense.linkDriver(&driver);
|
||||
current_sense.init();
|
||||
current_sense.gain_b *= -1;
|
||||
current_sense.skip_align = true;
|
||||
motor.linkCurrentSense(¤t_sense);
|
||||
|
||||
// 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();
|
||||
}
|
||||
@@ -0,0 +1,141 @@
|
||||
/**
|
||||
*
|
||||
* Hall sensor velocity motion control example, modified to demonstrate usage of SmoothingSensor
|
||||
* Steps:
|
||||
* 1) Configure the motor and sensor
|
||||
* 2) Run the code
|
||||
* 3) Set the target velocity (in radians per second) from serial terminal
|
||||
* 4) Try with and without smoothing to see the difference (send E1 and E0 commands 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>
|
||||
#include <SimpleFOCDrivers.h>
|
||||
#include <encoders/smoothing/SmoothingSensor.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);
|
||||
// wrapper instance
|
||||
SmoothingSensor smooth(sensor, motor);
|
||||
|
||||
// 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 enableSmoothing(char* cmd) {
|
||||
float enable;
|
||||
command.scalar(&enable, cmd);
|
||||
motor.linkSensor(enable == 0 ? (Sensor*)&sensor : (Sensor*)&smooth);
|
||||
}
|
||||
|
||||
void setup() {
|
||||
|
||||
// initialize sensor sensor hardware
|
||||
sensor.init();
|
||||
sensor.enableInterrupts(doA, doB); //, doC);
|
||||
// software interrupts
|
||||
PciManager.registerListener(&listenerIndex);
|
||||
// set SmoothingSensor phase correction for hall sensors
|
||||
smooth.phase_correction = -_PI_6;
|
||||
// link the SmoothingSensor to the motor
|
||||
motor.linkSensor(&smooth);
|
||||
|
||||
// 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");
|
||||
|
||||
// add smoothing enable/disable command E (send E0 to use hall sensor alone, or E1 to use smoothing)
|
||||
command.add('E', enableSmoothing, "enable smoothing");
|
||||
|
||||
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();
|
||||
}
|
||||
Reference in New Issue
Block a user