|
| 1 | +#include <SimpleFOC.h> |
| 2 | + |
| 3 | +// Only pins 2 and 3 are supported |
| 4 | +#define arduinoInt1 2 // Arduino UNO interrupt 0 |
| 5 | +#define arduinoInt2 3 // Arduino UNO interrupt 1 |
| 6 | + |
| 7 | +// BLDCMotor( int phA, int phB, int phC, int pp, int en) |
| 8 | +// - phA, phB, phC - motor A,B,C phase pwm pins |
| 9 | +// - pp - pole pair number |
| 10 | +// - enable pin - (optional input) |
| 11 | +BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8); |
| 12 | +// Encoder(int encA, int encB , int cpr, int index) |
| 13 | +// - encA, encB - encoder A and B pins |
| 14 | +// - ppr - impulses per rotation (cpr=ppr*4) |
| 15 | +// - index pin - (optional input) |
| 16 | +Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192); |
| 17 | + |
| 18 | +// Interrupt rutine intialisation |
| 19 | +// channel A and B callbacks |
| 20 | +void doA(){encoder.handleA();} |
| 21 | +void doB(){encoder.handleB();} |
| 22 | + |
| 23 | + |
| 24 | +void setup() { |
| 25 | + // debugging port |
| 26 | + Serial.begin(115200); |
| 27 | + |
| 28 | + // check if you need internal pullups |
| 29 | + // Quadrature::ENABLE - CPR = 4xPPR - default |
| 30 | + // Quadrature::DISABLE - CPR = PPR |
| 31 | + encoder.quadrature = Quadrature::ENABLE; |
| 32 | + |
| 33 | + // check if you need internal pullups |
| 34 | + // Pullup::EXTERN - external pullup added - dafault |
| 35 | + // Pullup::INTERN - needs internal arduino pullup |
| 36 | + encoder.pullup = Pullup::EXTERN; |
| 37 | + |
| 38 | + // initialise encoder hardware |
| 39 | + encoder.init(); |
| 40 | + // hardware interrupt enable |
| 41 | + encoder.enableInterrupts(doA, doB); |
| 42 | + |
| 43 | + // power supply voltage |
| 44 | + // default 12V |
| 45 | + motor.voltage_power_supply = 12; |
| 46 | + |
| 47 | + // set control loop type to be used |
| 48 | + // ControlType::voltage |
| 49 | + // ControlType::velocity |
| 50 | + // ControlType::angle |
| 51 | + motor.controller = ControlType::velocity; |
| 52 | + |
| 53 | + // contoller configuration based on the controll type |
| 54 | + // velocity PI controller parameters |
| 55 | + // default P=0.5 I = 10 |
| 56 | + motor.PI_velocity.P = 0.2; |
| 57 | + motor.PI_velocity.I = 20; |
| 58 | + //defualt voltage_power_supply/2 |
| 59 | + motor.PI_velocity.voltage_limit = 6; |
| 60 | + // jerk control using voltage voltage ramp |
| 61 | + // default value is 300 volts per sec ~ 0.3V per millisecond |
| 62 | + motor.PI_velocity.voltage_ramp = 1000; |
| 63 | + |
| 64 | + // velocity low pass filtering |
| 65 | + // default 5ms - try different values to see what is the best. |
| 66 | + // the lower the less filtered |
| 67 | + motor.LPF_velocity.Tf = 0.01; |
| 68 | + |
| 69 | + // use debugging with serial for motor init |
| 70 | + // comment out if not needed |
| 71 | + motor.useDebugging(Serial); |
| 72 | + |
| 73 | + // link the motor to the sensor |
| 74 | + motor.linkSensor(&encoder); |
| 75 | + |
| 76 | + // intialise motor |
| 77 | + motor.init(); |
| 78 | + // align encoder and start FOC |
| 79 | + motor.initFOC(); |
| 80 | + |
| 81 | + Serial.println("FOC ready.\n"); |
| 82 | + Serial.println("Update all the PI contorller paramters from the serial temrinal:"); |
| 83 | + Serial.println("- Type P100.2 to you the PI_velocity.P in 100.2"); |
| 84 | + Serial.println("- Type I72.32 to you the PI_velocity.I in 72.32\n"); |
| 85 | + Serial.println("Update the time constant of the velocity filter:"); |
| 86 | + Serial.println("- Type F0.03 to you the LPF_velocity.Tf in 0.03\n"); |
| 87 | + Serial.println("Check the loop executoion time (average):"); |
| 88 | + Serial.println("- Type T\n"); |
| 89 | + Serial.println("To change the target valeocity just enter the value without any prefix.\n"); |
| 90 | + |
| 91 | + Serial.println("Initial control parameters:"); |
| 92 | + Serial.print("PI velocity P: "); |
| 93 | + Serial.print(motor.PI_velocity.P); |
| 94 | + Serial.print(",\t I: "); |
| 95 | + Serial.print(motor.PI_velocity.I); |
| 96 | + Serial.print(",\t Low passs filter Tf: "); |
| 97 | + Serial.println(motor.LPF_velocity.Tf,4); |
| 98 | + |
| 99 | + _delay(1000); |
| 100 | +} |
| 101 | + |
| 102 | +// velocity set point variable |
| 103 | +float target_velocity = 0; |
| 104 | +// loop stats variables |
| 105 | +unsigned long t = 0; |
| 106 | +long timestamp = _micros(); |
| 107 | + |
| 108 | +void loop() { |
| 109 | + // iterative state calculation calculating angle |
| 110 | + // and setting FOC pahse voltage |
| 111 | + // the faster you run this funciton the better |
| 112 | + // in arduino loop it should have ~1kHz |
| 113 | + // the best would be to be in ~10kHz range |
| 114 | + motor.loopFOC(); |
| 115 | + |
| 116 | + // iterative function setting the outter loop target |
| 117 | + // velocity, position or voltage |
| 118 | + // this funciton can be run at much lower frequency than loopFOC funciton |
| 119 | + // it can go as low as ~50Hz |
| 120 | + motor.move(target_velocity); |
| 121 | + |
| 122 | + // function intended to be used with serial plotter to monitor motor variables |
| 123 | + // significantly slowing the execution down!!!! |
| 124 | + // motor_monitor(); |
| 125 | + |
| 126 | + // keep track of loop number |
| 127 | + t++; |
| 128 | +} |
| 129 | + |
| 130 | +// utility function intended to be used with serial plotter to monitor motor variables |
| 131 | +// significantly slowing the execution down!!!! |
| 132 | +void motor_monitor() { |
| 133 | + switch (motor.controller) { |
| 134 | + case ControlType::velocity: |
| 135 | + Serial.print(motor.voltage_q); |
| 136 | + Serial.print("\t"); |
| 137 | + Serial.print(motor.shaft_velocity_sp); |
| 138 | + Serial.print("\t"); |
| 139 | + Serial.println(motor.shaft_velocity); |
| 140 | + break; |
| 141 | + case ControlType::angle: |
| 142 | + Serial.print(motor.voltage_q); |
| 143 | + Serial.print("\t"); |
| 144 | + Serial.print(motor.shaft_angle_sp); |
| 145 | + Serial.print("\t"); |
| 146 | + Serial.println(motor.shaft_angle); |
| 147 | + break; |
| 148 | + case ControlType::voltage: |
| 149 | + Serial.print(motor.voltage_q); |
| 150 | + Serial.print("\t"); |
| 151 | + Serial.println(motor.shaft_velocity); |
| 152 | + break; |
| 153 | + } |
| 154 | +} |
| 155 | + |
| 156 | +// Serial communication callback function |
| 157 | +// gets the target value from the user |
| 158 | +void serialEvent() { |
| 159 | + // a string to hold incoming data |
| 160 | + static String inputString; |
| 161 | + while (Serial.available()) { |
| 162 | + // get the new byte: |
| 163 | + char inChar = (char)Serial.read(); |
| 164 | + // add it to the inputString: |
| 165 | + inputString += inChar; |
| 166 | + // if the incoming character is a newline |
| 167 | + // end of input |
| 168 | + if (inChar == '\n') { |
| 169 | + if(inputString.charAt(0) == 'P'){ |
| 170 | + motor.PI_velocity.P = inputString.substring(1).toFloat(); |
| 171 | + Serial.print("PI velocity P: "); |
| 172 | + Serial.print(motor.PI_velocity.P); |
| 173 | + Serial.print(",\t I: "); |
| 174 | + Serial.print(motor.PI_velocity.I); |
| 175 | + Serial.print(",\t Low passs filter Tf: "); |
| 176 | + Serial.println(motor.LPF_velocity.Tf,4); |
| 177 | + }else if(inputString.charAt(0) == 'I'){ |
| 178 | + motor.PI_velocity.I = inputString.substring(1).toFloat(); |
| 179 | + Serial.print("PI velocity P: "); |
| 180 | + Serial.print(motor.PI_velocity.P); |
| 181 | + Serial.print(",\t I: "); |
| 182 | + Serial.print(motor.PI_velocity.I); |
| 183 | + Serial.print(",\t Low passs filter Tf: "); |
| 184 | + Serial.println(motor.LPF_velocity.Tf,4); |
| 185 | + }else if(inputString.charAt(0) == 'F'){ |
| 186 | + motor.LPF_velocity.Tf = inputString.substring(1).toFloat(); |
| 187 | + Serial.print("PI velocity P: "); |
| 188 | + Serial.print(motor.PI_velocity.P); |
| 189 | + Serial.print(",\t I: "); |
| 190 | + Serial.print(motor.PI_velocity.I); |
| 191 | + Serial.print(",\t Low passs filter Tf: "); |
| 192 | + Serial.println(motor.LPF_velocity.Tf,4); |
| 193 | + }else if(inputString.charAt(0) == 'T'){ |
| 194 | + Serial.print("Average loop time is (microseconds): "); |
| 195 | + Serial.println((_micros() - timestamp)/t); |
| 196 | + t = 0; |
| 197 | + timestamp = _micros(); |
| 198 | + }else{ |
| 199 | + target_velocity = inputString.toFloat(); |
| 200 | + Serial.print("Tagret Velocity: "); |
| 201 | + Serial.println(target_velocity); |
| 202 | + inputString = ""; |
| 203 | + } |
| 204 | + inputString = ""; |
| 205 | + } |
| 206 | + } |
| 207 | +} |
0 commit comments