#include <SimpleFOC.h>
// BLDC motor instance BLDCMotor(polepairs, (R), (KV), (L))
BLDCMotor motor = BLDCMotor();
// Stepper motor instance StepperMotor(polepairs, (R), (KV), (L))
StepperMotor motor = StepperMotor();
// BLDC driver instance BLDCDriver3PWM(phA, phB, phC, (en))
BLDCDriver3PWM driver = BLDCDriver3PWM();
// BLDC driver instance BLDCDriver6PWM(phA_h, phA_l, phB_h, phB_l, phC_h, phC_l, (en))
BLDCDriver6PWM driver = BLDCDriver6PWM();
// Stepper driver instance StepperDriver4PWM(pwm1, ph1A, ph1B, pwm2, ph2A, ph2B, (en1), (en2))
StepperDriver2PWM driver = StepperDriver2PWM();
// Stepper driver instance StepperDriver2PWM(pwm1, dir1, pwm2, dir2, (en1), (en2))
StepperDriver2PWM driver = StepperDriver2PWM();
// Stepper driver instance StepperDriver4PWM(ph1A, ph1B, ph2A, ph2B, (en1), (en2))
StepperDriver4PWM driver = StepperDriver4PWM();
// BLDC driver instance BLDCDriver6PWM(phA_h, phA_l, phB_h, phB_l, phC_h, phC_l, (en))
BLDCDriver6PWM driver = BLDCDriver6PWM(A_PHASE_UH, A_PHASE_UL, A_PHASE_VH, A_PHASE_VL, A_PHASE_WH, A_PHASE_WL);
// BLDC driver instance BLDCDriver3PWM(phA, phB, phC, (en))
BLDCDriver3PWM driver = BLDCDriver3PWM();
// BLDC driver instance BLDCDriver3PWM(phA, phB, phC, (en))
BLDCDriver3PWM driver = BLDCDriver3PWM();
// Stepper driver instance StepperDriver4PWM(ph1A, ph1B, ph2A, ph2B, (en1), (en2))
StepperDriver4PWM driver = StepperDriver4PWM();
// position / angle sensor instance Encoder(encA, encB , cpr, (index))
// these should be hardware interrupt pins, these are not the same for all microcontrollers https://docs.simplefoc.com/encoder#step-3-encoder-interrupt-setup
Encoder sensor = Encoder();
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
void doIndex(){sensor.handleIndex();}
// position / angle sensor instance HallSensor(hallA, hallB , hallC , pole pairs)
HallSensor sensor = HallSensor();
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
void doC(){sensor.handleC();}
// position / angle sensor instance MagneticSensorSPI(chip select, bit resolution, angle register)
MagneticSensorSPI sensor = MagneticSensorSPI();
// position / angle sensor instance MagneticSensorI2C(chip address, bit resolution, angle read register msb, used msb register bits)
MagneticSensorI2C sensor = MagneticSensorI2C();
// position / angle sensor instance MagneticSensorAnalog(analog pin, minimum, maximum)
MagneticSensorAnalog sensor = MagneticSensorAnalog();
// position / angle sensor instance MagneticSensorPWM(PWM pin, minimum pulse, maximum pulse)
MagneticSensorPWM sensor = MagneticSensorPWM();
// create the buffering function
void doPWM(){sensor.handlePWM();}
// position / angle sensor instance MagneticSensorSPI(chip select, AS5147_SPI)
MagneticSensorSPI sensor = MagneticSensorSPI(, AS5147_SPI);
// position / angle sensor instance MagneticSensorSPI(chip select, MA730_SPI)
MagneticSensorSPI sensor = MagneticSensorSPI(, MA730_SPI);
// position / angle sensor instance
MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);
// position / angle sensor instance
MagneticSensorI2C sensor = MagneticSensorI2C(AS5048_I2C);
// inline current sense instance InlineCurrentSense(R, gain, phA, phB, (phC))
InlineCurrentSense currentsense = InlineCurrentSense();
// lowside current sense instance LowsideCurrentSense(R, gain, phA, phB, (phC))
LowsideCurrentSense currentsense = LowsideCurrentSense();
// inline current sense instance InlineCurrentSense(R, gain, phA, phB, (phC))
InlineCurrentSense currentsense = InlineCurrentSense(0.01, 50);
// inline current sense instance InlineCurrentSense(R, gain, phA, phB, phC)
InlineCurrentSense currentsense = InlineCurrentSense(0.003, -64.0/7.0, A_OP1_OUT, A_OP2_OUT, A_OP3_OUT);
// commander instance
Commander command = Commander(Serial);
void doTarget(char* cmd){command.motion(&motor, cmd);}
void setup() {
// start serial
Serial.begin(115200);
// set I2C clock speed
Wire.setClock(400000);
// USE_EXTERN is default (1k - 5k recommended), change to USE_INTERN if needed
sensor.pullup = Pullup::USE_EXTERN;
// initialize sensor
sensor.init();
// enable encoder interrupts
sensor.enableInterrupts(doA, doB, doIndex);
// enable Hall effect interrupts
sensor.enableInterrupts(doA, doB, doC);
// enable PWM interrupts
sensor.enableInterrupt(doPWM);
// link sensor to motor
motor.linkSensor(&sensor);
// set power supply voltage
driver.voltage_power_supply = ;
// set driver voltage limit, this phase voltage
driver.voltage_limit = ;
// initialize driver
driver.init();
// link driver to motor
motor.linkDriver(&driver);
// link driver to current sense
currentsense.linkDriver(&driver);
// set motion control type to torque (default)
motor.controller = MotionControlType::torque;
// set motion control type to velocity
motor.controller = MotionControlType::velocity;
// set motion control type to angle / position
motor.controller = MotionControlType::angle;
// set motion control type to velocity openloop
motor.controller = MotionControlType::velocity_openloop;
// set motion control type to angle / postion openloop
motor.controller = MotionControlType::angle_openloop;
// set torque control type to voltage (default)
motor.torque_controller = TorqueControlType::voltage;
// set torque control type to DC current
motor.torque_controller = TorqueControlType::dc_current;
// set torque control type to FOC current
motor.torque_controller = TorqueControlType::foc_current;
// set FOC modulation type to sinusoidal
motor.foc_modulation = FOCModulationType::SinePWM;
// set FOC modulation type to trapezoidal 120
motor.foc_modulation = FOCModulationType::Trapezoid_120;
// set FOC modulation type to trapezoidal 150
motor.foc_modulation = FOCModulationType::Trapezoid_150;
// set FOC modulation type to space vector modulation
motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
// velocity PID controller
motor.PID_velocity.P = ;
motor.PID_velocity.I = ;
motor.PID_velocity.D = ;
// angle / position P controller
motor.P_angle.P = ;
// set motor voltage limit, this limits Vq
motor.voltage_limit = ;
// set motor velocity limit
motor.velocity_limit = ;
// set motor current limit, this limits Iq
motor.current_limit = ;
// use monitoring
motor.useMonitoring(Serial);
// initialize motor
motor.init();
// initialize current sensing and link it to the motor
// https://docs.simplefoc.com/inline_current_sense#where-to-place-the-current_sense-configuration-in-your-foc-code
currentsense.init();
motor.linkCurrentSense(¤tsense);
// align sensor and start FOC
motor.initFOC();
// add command to commander
command.add('M', doTarget, "target");
_delay(1000);
}
void loop() {
// main FOC algorithm function, the higher the execution frequency, the better, don't put delays in the loop
motor.loopFOC();
// this function can be run at much lower frequency than loopFOC()
motor.move();
// significantly slowing the execution down
motor.monitor();
// user communication
command.run();
}