Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Fork of ES_CW2_Starter by
main.cpp@11:1f596bf4182b, 2017-03-09 (annotated)
- Committer:
- david_s95
- Date:
- Thu Mar 09 12:17:32 2017 +0000
- Revision:
- 11:1f596bf4182b
- Parent:
- 10:0309d6c49f26
- Child:
- 12:8ea29b18d289
Removed some unused old functions.
Who changed what in which revision?
| User | Revision | Line number | New contents of line |
|---|---|---|---|
| estott | 0:de4320f74764 | 1 | #include "mbed.h" |
| estott | 0:de4320f74764 | 2 | #include "rtos.h" |
| david_s95 | 5:e5313b695302 | 3 | #include <string> |
| david_s95 | 10:0309d6c49f26 | 4 | #include "PID.h" |
| david_s95 | 10:0309d6c49f26 | 5 | |
| david_s95 | 10:0309d6c49f26 | 6 | //PID controller configuration |
| david_s95 | 10:0309d6c49f26 | 7 | float PIDrate = 0.2; |
| david_s95 | 10:0309d6c49f26 | 8 | float Kc = 1.0; |
| david_s95 | 10:0309d6c49f26 | 9 | float Ti = 0.0; |
| david_s95 | 10:0309d6c49f26 | 10 | float Td = 0.0; |
| david_s95 | 10:0309d6c49f26 | 11 | float speedControl = 0; |
| david_s95 | 10:0309d6c49f26 | 12 | PID controller(Kc, Ti, Td, PIDrate); |
| david_s95 | 10:0309d6c49f26 | 13 | Thread VPIDthread; |
| estott | 0:de4320f74764 | 14 | |
| estott | 0:de4320f74764 | 15 | //Photointerrupter input pins |
| estott | 0:de4320f74764 | 16 | #define I1pin D2 |
| estott | 2:4e88faab6988 | 17 | #define I2pin D11 |
| estott | 2:4e88faab6988 | 18 | #define I3pin D12 |
| estott | 2:4e88faab6988 | 19 | |
| estott | 2:4e88faab6988 | 20 | //Incremental encoder input pins |
| estott | 2:4e88faab6988 | 21 | #define CHA D7 |
| david_s95 | 5:e5313b695302 | 22 | #define CHB D8 |
| estott | 0:de4320f74764 | 23 | |
| estott | 0:de4320f74764 | 24 | //Motor Drive output pins //Mask in output byte |
| estott | 2:4e88faab6988 | 25 | #define L1Lpin D4 //0x01 |
| estott | 2:4e88faab6988 | 26 | #define L1Hpin D5 //0x02 |
| estott | 2:4e88faab6988 | 27 | #define L2Lpin D3 //0x04 |
| estott | 2:4e88faab6988 | 28 | #define L2Hpin D6 //0x08 |
| estott | 2:4e88faab6988 | 29 | #define L3Lpin D9 //0x10 |
| estott | 0:de4320f74764 | 30 | #define L3Hpin D10 //0x20 |
| estott | 0:de4320f74764 | 31 | |
| david_s95 | 5:e5313b695302 | 32 | //Define sized for command arrays |
| david_s95 | 5:e5313b695302 | 33 | #define ARRAYSIZE 8 |
| david_s95 | 5:e5313b695302 | 34 | |
| estott | 0:de4320f74764 | 35 | //Mapping from sequential drive states to motor phase outputs |
| estott | 0:de4320f74764 | 36 | /* |
| estott | 0:de4320f74764 | 37 | State L1 L2 L3 |
| estott | 0:de4320f74764 | 38 | 0 H - L |
| estott | 0:de4320f74764 | 39 | 1 - H L |
| estott | 0:de4320f74764 | 40 | 2 L H - |
| estott | 0:de4320f74764 | 41 | 3 L - H |
| estott | 0:de4320f74764 | 42 | 4 - L H |
| estott | 0:de4320f74764 | 43 | 5 H L - |
| estott | 0:de4320f74764 | 44 | 6 - - - |
| estott | 0:de4320f74764 | 45 | 7 - - - |
| estott | 0:de4320f74764 | 46 | */ |
| estott | 0:de4320f74764 | 47 | //Drive state to output table |
| david_s95 | 9:575b29cbf5e4 | 48 | //const int8_t driveTable[] = {0x12,0x18,0x09,0x21,0x24,0x06,0x00,0x00}; |
| david_s95 | 9:575b29cbf5e4 | 49 | const int8_t driveTable[6] = {0x38, 0x2C, 0x0E, 0x0B, 0x23, 0x32}; |
| david_s95 | 9:575b29cbf5e4 | 50 | |
| david_s95 | 9:575b29cbf5e4 | 51 | //const int8_t cwState[7] = {0, 4, 0, 5, 2, 3, 1}; |
| david_s95 | 9:575b29cbf5e4 | 52 | //const int8_t AcwState[7] = {0, 2, 4, 3, 0, 1, 5}; |
| david_s95 | 9:575b29cbf5e4 | 53 | //const int8_t cwState[7] = {0x00, 0x23, 0x38, 0x32, 0x0E, 0x0B, 0x2C}; |
| david_s95 | 9:575b29cbf5e4 | 54 | //const int8_t AcwState[7] = {0x00, 0x0E, 0x23, 0x0B, 0x38, 0x2C, 0x32}; |
| david_s95 | 9:575b29cbf5e4 | 55 | const int8_t AcwState[7] = {0x00, 0x23, 0x38, 0x32, 0x0E, 0x0B, 0x2C}; |
| david_s95 | 9:575b29cbf5e4 | 56 | const int8_t cwState[7] = {0x00, 0x0E, 0x23, 0x0B, 0x38, 0x2C, 0x32}; |
| estott | 2:4e88faab6988 | 57 | |
| estott | 0:de4320f74764 | 58 | //Mapping from interrupter inputs to sequential rotor states. 0x00 and 0x07 are not valid |
| david_s95 | 9:575b29cbf5e4 | 59 | //const int8_t stateMap[] = {0x07,0x05,0x03,0x04,0x01,0x00,0x02,0x07}; |
| estott | 2:4e88faab6988 | 60 | //const int8_t stateMap[] = {0x07,0x01,0x03,0x02,0x05,0x00,0x04,0x07}; //Alternative if phase order of input or drive is reversed |
| estott | 2:4e88faab6988 | 61 | |
| estott | 2:4e88faab6988 | 62 | //Phase lead to make motor spin |
| david_s95 | 9:575b29cbf5e4 | 63 | //int8_t lead = -2; //2 for forwards, -2 for backwards |
| estott | 0:de4320f74764 | 64 | |
| estott | 0:de4320f74764 | 65 | //Status LED |
| estott | 0:de4320f74764 | 66 | DigitalOut led1(LED1); |
| estott | 0:de4320f74764 | 67 | |
| estott | 0:de4320f74764 | 68 | //Photointerrupter inputs |
| david_s95 | 9:575b29cbf5e4 | 69 | DigitalIn I1(I1pin); |
| david_s95 | 9:575b29cbf5e4 | 70 | //InterruptIn I1(I1pin); |
| david_s95 | 9:575b29cbf5e4 | 71 | InterruptIn I2(I2pin); |
| estott | 2:4e88faab6988 | 72 | DigitalIn I3(I3pin); |
| estott | 0:de4320f74764 | 73 | |
| david_s95 | 8:77627657da80 | 74 | InterruptIn qA(CHA); |
| david_s95 | 8:77627657da80 | 75 | InterruptIn qB(CHB); |
| david_s95 | 8:77627657da80 | 76 | |
| estott | 0:de4320f74764 | 77 | //Motor Drive outputs |
| david_s95 | 9:575b29cbf5e4 | 78 | //DigitalOut L1L(L1Lpin); |
| david_s95 | 9:575b29cbf5e4 | 79 | //DigitalOut L1H(L1Hpin); |
| david_s95 | 9:575b29cbf5e4 | 80 | //DigitalOut L2L(L2Lpin); |
| david_s95 | 9:575b29cbf5e4 | 81 | //DigitalOut L2H(L2Hpin); |
| david_s95 | 9:575b29cbf5e4 | 82 | //DigitalOut L3L(L3Lpin); |
| david_s95 | 9:575b29cbf5e4 | 83 | //DigitalOut L3H(L3Hpin); |
| david_s95 | 5:e5313b695302 | 84 | DigitalOut clk(LED1); |
| david_s95 | 8:77627657da80 | 85 | DigitalOut Direction(LED2); |
| david_s95 | 9:575b29cbf5e4 | 86 | DigitalOut testpin(D13); |
| david_s95 | 9:575b29cbf5e4 | 87 | |
| david_s95 | 9:575b29cbf5e4 | 88 | //NOTE, BusOut declares things in reverse (ie, 0, 1, 2, 3) compared to binary represenation |
| david_s95 | 9:575b29cbf5e4 | 89 | BusOut motor(L1Lpin, L1Hpin, L2Lpin, L2Hpin, L3Lpin, L3Hpin); |
| david_s95 | 5:e5313b695302 | 90 | |
| david_s95 | 5:e5313b695302 | 91 | //Timeout function for rotating at set speed |
| david_s95 | 5:e5313b695302 | 92 | Timeout spinTimer; |
| david_s95 | 5:e5313b695302 | 93 | float spinWait = 10; |
| david_s95 | 5:e5313b695302 | 94 | float revsec = 0; |
| david_s95 | 5:e5313b695302 | 95 | |
| david_s95 | 7:5932ed0bad6d | 96 | //Timer used for calculating speed |
| david_s95 | 7:5932ed0bad6d | 97 | Timer speedTimer; |
| david_s95 | 10:0309d6c49f26 | 98 | float measuredRevs = 0, revtimer = 0; |
| david_s95 | 7:5932ed0bad6d | 99 | Ticker printSpeed; |
| david_s95 | 7:5932ed0bad6d | 100 | |
| david_s95 | 5:e5313b695302 | 101 | Serial pc(SERIAL_TX, SERIAL_RX); |
| david_s95 | 5:e5313b695302 | 102 | |
| david_s95 | 5:e5313b695302 | 103 | int8_t orState = 0; //Rotor offset at motor state 0 |
| david_s95 | 5:e5313b695302 | 104 | int8_t intState = 0; |
| david_s95 | 5:e5313b695302 | 105 | int8_t intStateOld = 0; |
| david_s95 | 9:575b29cbf5e4 | 106 | int position = 0; |
| david_s95 | 5:e5313b695302 | 107 | |
| david_s95 | 5:e5313b695302 | 108 | int i=0; |
| david_s95 | 10:0309d6c49f26 | 109 | int quadraturePosition=0; |
| david_s95 | 9:575b29cbf5e4 | 110 | bool spinCW=0; |
| david_s95 | 10:0309d6c49f26 | 111 | float u = 0; //Set point for VPI |
| david_s95 | 5:e5313b695302 | 112 | |
| estott | 0:de4320f74764 | 113 | //Set a given drive state |
| david_s95 | 5:e5313b695302 | 114 | void motorOut(int8_t driveState) |
| david_s95 | 5:e5313b695302 | 115 | { |
| david_s95 | 5:e5313b695302 | 116 | |
| david_s95 | 9:575b29cbf5e4 | 117 | //Set to zero |
| david_s95 | 9:575b29cbf5e4 | 118 | motor=0x2A; |
| david_s95 | 10:0309d6c49f26 | 119 | |
| david_s95 | 9:575b29cbf5e4 | 120 | //Go to next state |
| david_s95 | 9:575b29cbf5e4 | 121 | if(!spinCW) motor = AcwState[driveState]; |
| david_s95 | 9:575b29cbf5e4 | 122 | else motor = cwState[driveState]; |
| estott | 2:4e88faab6988 | 123 | //Lookup the output byte from the drive state. |
| david_s95 | 9:575b29cbf5e4 | 124 | // int8_t driveOut = driveTable[driveState & 0x07]; |
| david_s95 | 10:0309d6c49f26 | 125 | } |
| david_s95 | 5:e5313b695302 | 126 | |
| david_s95 | 10:0309d6c49f26 | 127 | inline void motorStop() |
| david_s95 | 10:0309d6c49f26 | 128 | { |
| david_s95 | 10:0309d6c49f26 | 129 | //revsec set to zero prevents recurring interrupt for constant speed |
| david_s95 | 10:0309d6c49f26 | 130 | revsec = 0; |
| david_s95 | 10:0309d6c49f26 | 131 | //0x2A turns all motor transistors off to prevent any power usage |
| david_s95 | 10:0309d6c49f26 | 132 | motor = 0x2A; |
| david_s95 | 5:e5313b695302 | 133 | } |
| david_s95 | 5:e5313b695302 | 134 | |
| david_s95 | 5:e5313b695302 | 135 | //Convert photointerrupter inputs to a rotor state |
| david_s95 | 5:e5313b695302 | 136 | inline int8_t readRotorState() |
| david_s95 | 5:e5313b695302 | 137 | { |
| david_s95 | 9:575b29cbf5e4 | 138 | return (I1 + 2*I2 + 4*I3); |
| david_s95 | 5:e5313b695302 | 139 | } |
| estott | 0:de4320f74764 | 140 | |
| david_s95 | 5:e5313b695302 | 141 | //Basic synchronisation routine |
| david_s95 | 5:e5313b695302 | 142 | int8_t motorHome() |
| david_s95 | 5:e5313b695302 | 143 | { |
| estott | 0:de4320f74764 | 144 | //Put the motor in drive state 0 and wait for it to stabilise |
| david_s95 | 9:575b29cbf5e4 | 145 | motor=cwState[1]; |
| estott | 0:de4320f74764 | 146 | wait(1.0); |
| david_s95 | 10:0309d6c49f26 | 147 | |
| david_s95 | 9:575b29cbf5e4 | 148 | position = 0; |
| david_s95 | 5:e5313b695302 | 149 | |
| estott | 0:de4320f74764 | 150 | //Get the rotor state |
| estott | 2:4e88faab6988 | 151 | return readRotorState(); |
| estott | 0:de4320f74764 | 152 | } |
| david_s95 | 5:e5313b695302 | 153 | |
| david_s95 | 5:e5313b695302 | 154 | void fixedSpeed() |
| david_s95 | 5:e5313b695302 | 155 | { |
| david_s95 | 6:4edbe75736d9 | 156 | //Read current motor state |
| david_s95 | 10:0309d6c49f26 | 157 | // clk=!clk; |
| david_s95 | 10:0309d6c49f26 | 158 | // {0x38, 0x2C, 0x0E, 0x0B, 0x23, 0x32}; |
| david_s95 | 10:0309d6c49f26 | 159 | //if(spinCW) { |
| david_s95 | 10:0309d6c49f26 | 160 | // switch(motor) { |
| david_s95 | 10:0309d6c49f26 | 161 | // case 0x38: |
| david_s95 | 10:0309d6c49f26 | 162 | // motor=0x2C; |
| david_s95 | 10:0309d6c49f26 | 163 | // break; |
| david_s95 | 10:0309d6c49f26 | 164 | // case 0x2C: |
| david_s95 | 10:0309d6c49f26 | 165 | // motor=0x0E; |
| david_s95 | 10:0309d6c49f26 | 166 | // break; |
| david_s95 | 10:0309d6c49f26 | 167 | // case 0x0E: |
| david_s95 | 10:0309d6c49f26 | 168 | // motor=0x0B; |
| david_s95 | 10:0309d6c49f26 | 169 | // break; |
| david_s95 | 10:0309d6c49f26 | 170 | // case 0x0B: |
| david_s95 | 10:0309d6c49f26 | 171 | // motor=0x23; |
| david_s95 | 10:0309d6c49f26 | 172 | // break; |
| david_s95 | 10:0309d6c49f26 | 173 | // case 0x23: |
| david_s95 | 10:0309d6c49f26 | 174 | // motor=0x32; |
| david_s95 | 10:0309d6c49f26 | 175 | // break; |
| david_s95 | 10:0309d6c49f26 | 176 | // case 0x32: |
| david_s95 | 10:0309d6c49f26 | 177 | // motor=0x38; |
| david_s95 | 10:0309d6c49f26 | 178 | // break; |
| david_s95 | 10:0309d6c49f26 | 179 | // } |
| david_s95 | 10:0309d6c49f26 | 180 | // } else { |
| david_s95 | 10:0309d6c49f26 | 181 | // switch(motor) { |
| david_s95 | 10:0309d6c49f26 | 182 | // case 0x38: |
| david_s95 | 10:0309d6c49f26 | 183 | // motor=0x32; |
| david_s95 | 10:0309d6c49f26 | 184 | // break; |
| david_s95 | 10:0309d6c49f26 | 185 | // case 0x2C: |
| david_s95 | 10:0309d6c49f26 | 186 | // motor=0x38; |
| david_s95 | 10:0309d6c49f26 | 187 | // break; |
| david_s95 | 10:0309d6c49f26 | 188 | // case 0x0E: |
| david_s95 | 10:0309d6c49f26 | 189 | // motor=0x2C; |
| david_s95 | 10:0309d6c49f26 | 190 | // break; |
| david_s95 | 10:0309d6c49f26 | 191 | // case 0x0B: |
| david_s95 | 10:0309d6c49f26 | 192 | // motor=0x0E; |
| david_s95 | 10:0309d6c49f26 | 193 | // break; |
| david_s95 | 10:0309d6c49f26 | 194 | // case 0x23: |
| david_s95 | 10:0309d6c49f26 | 195 | // motor=0x0B; |
| david_s95 | 10:0309d6c49f26 | 196 | // break; |
| david_s95 | 10:0309d6c49f26 | 197 | // case 0x32: |
| david_s95 | 10:0309d6c49f26 | 198 | // motor=0x23; |
| david_s95 | 10:0309d6c49f26 | 199 | // break; |
| david_s95 | 10:0309d6c49f26 | 200 | // } |
| david_s95 | 10:0309d6c49f26 | 201 | // } |
| david_s95 | 5:e5313b695302 | 202 | intState = readRotorState(); |
| david_s95 | 6:4edbe75736d9 | 203 | //Increment state machine to next state |
| david_s95 | 9:575b29cbf5e4 | 204 | motorOut(intState); |
| david_s95 | 6:4edbe75736d9 | 205 | //If spinning is required, attach the necessary wait to the |
| david_s95 | 6:4edbe75736d9 | 206 | //timeout interrupt to call this function again and |
| david_s95 | 6:4edbe75736d9 | 207 | //keep the motor spinning at the right speed |
| david_s95 | 5:e5313b695302 | 208 | if(revsec) spinTimer.attach(&fixedSpeed, spinWait); |
| david_s95 | 5:e5313b695302 | 209 | } |
| david_s95 | 5:e5313b695302 | 210 | |
| david_s95 | 10:0309d6c49f26 | 211 | void rps() |
| david_s95 | 7:5932ed0bad6d | 212 | { |
| david_s95 | 10:0309d6c49f26 | 213 | |
| david_s95 | 10:0309d6c49f26 | 214 | clk=!clk; |
| david_s95 | 10:0309d6c49f26 | 215 | speedTimer.stop(); |
| david_s95 | 10:0309d6c49f26 | 216 | revtimer = speedTimer.read_ms(); |
| david_s95 | 10:0309d6c49f26 | 217 | speedTimer.reset(); |
| david_s95 | 10:0309d6c49f26 | 218 | speedTimer.start(); |
| david_s95 | 10:0309d6c49f26 | 219 | |
| david_s95 | 10:0309d6c49f26 | 220 | measuredRevs = 1000/(revtimer); |
| david_s95 | 10:0309d6c49f26 | 221 | quadraturePosition=0; |
| david_s95 | 10:0309d6c49f26 | 222 | |
| david_s95 | 7:5932ed0bad6d | 223 | } |
| david_s95 | 7:5932ed0bad6d | 224 | |
| david_s95 | 10:0309d6c49f26 | 225 | void VPID() |
| david_s95 | 10:0309d6c49f26 | 226 | { |
| david_s95 | 10:0309d6c49f26 | 227 | while(1) { |
| david_s95 | 10:0309d6c49f26 | 228 | controller.setSetPoint(revsec); |
| david_s95 | 10:0309d6c49f26 | 229 | // printf("revsec: %2.3f\r\n", revsec); |
| david_s95 | 10:0309d6c49f26 | 230 | controller.setProcessValue(measuredRevs); |
| david_s95 | 10:0309d6c49f26 | 231 | speedControl = controller.compute(); |
| david_s95 | 10:0309d6c49f26 | 232 | // printf("speed setpoint: %2.3f\r\n", speedControl); |
| david_s95 | 10:0309d6c49f26 | 233 | Thread::wait(PIDrate); |
| david_s95 | 10:0309d6c49f26 | 234 | } |
| david_s95 | 10:0309d6c49f26 | 235 | } |
| david_s95 | 10:0309d6c49f26 | 236 | /* |
| david_s95 | 7:5932ed0bad6d | 237 | |
| david_s95 | 9:575b29cbf5e4 | 238 | void edgeRiseA() |
| david_s95 | 9:575b29cbf5e4 | 239 | { |
| david_s95 | 8:77627657da80 | 240 | pos++; |
| david_s95 | 9:575b29cbf5e4 | 241 | if(pos>=468) { |
| david_s95 | 8:77627657da80 | 242 | // Direction=!Direction; |
| david_s95 | 8:77627657da80 | 243 | pos=pos%468; |
| david_s95 | 8:77627657da80 | 244 | // testpin=!testpin; |
| david_s95 | 8:77627657da80 | 245 | } |
| david_s95 | 8:77627657da80 | 246 | if(qB) DIR = 0; |
| david_s95 | 8:77627657da80 | 247 | else DIR = 1; |
| david_s95 | 9:575b29cbf5e4 | 248 | // clk=DIR; |
| david_s95 | 8:77627657da80 | 249 | //CLOCKWISE: A rises before B -> On A edge, B low -> DIR = 1 |
| david_s95 | 8:77627657da80 | 250 | //ANTICLOCKWISE: B rises before A -> On A edge, B high-> DIR = 0 |
| david_s95 | 8:77627657da80 | 251 | } |
| david_s95 | 8:77627657da80 | 252 | |
| david_s95 | 9:575b29cbf5e4 | 253 | void edgeIncr() |
| david_s95 | 9:575b29cbf5e4 | 254 | { |
| david_s95 | 8:77627657da80 | 255 | pos++; |
| david_s95 | 9:575b29cbf5e4 | 256 | if(pos>=468) { |
| david_s95 | 8:77627657da80 | 257 | // Direction=!Direction; |
| david_s95 | 8:77627657da80 | 258 | pos=pos%468; |
| david_s95 | 8:77627657da80 | 259 | // testpin=!testpin; |
| david_s95 | 8:77627657da80 | 260 | } |
| david_s95 | 9:575b29cbf5e4 | 261 | }*/ |
| david_s95 | 8:77627657da80 | 262 | |
| david_s95 | 9:575b29cbf5e4 | 263 | //#define WAIT 2 |
| mengkiang | 4:f8a9ce214db9 | 264 | //Main function |
| david_s95 | 5:e5313b695302 | 265 | int main() |
| david_s95 | 5:e5313b695302 | 266 | { |
| david_s95 | 9:575b29cbf5e4 | 267 | pc.printf("spin\n\r"); |
| david_s95 | 10:0309d6c49f26 | 268 | |
| david_s95 | 9:575b29cbf5e4 | 269 | // motor = 0x0E; |
| david_s95 | 10:0309d6c49f26 | 270 | /* while(1){ |
| david_s95 | 10:0309d6c49f26 | 271 | motor=0x38; |
| david_s95 | 10:0309d6c49f26 | 272 | printf("0x38\r\n"); |
| david_s95 | 10:0309d6c49f26 | 273 | wait(WAIT); |
| david_s95 | 10:0309d6c49f26 | 274 | position = I1 + 2*I2 + 4*I3; |
| david_s95 | 10:0309d6c49f26 | 275 | printf("position: %d\r\n", position); |
| david_s95 | 10:0309d6c49f26 | 276 | motor=0x2C; |
| david_s95 | 10:0309d6c49f26 | 277 | printf("0x2C\r\n"); |
| david_s95 | 10:0309d6c49f26 | 278 | wait(WAIT); |
| david_s95 | 10:0309d6c49f26 | 279 | position = I1 + 2*I2 + 4*I3; |
| david_s95 | 10:0309d6c49f26 | 280 | printf("position: %d\r\n", position); |
| david_s95 | 10:0309d6c49f26 | 281 | motor=0x0E; |
| david_s95 | 10:0309d6c49f26 | 282 | printf("0x0E\r\n"); |
| david_s95 | 10:0309d6c49f26 | 283 | wait(WAIT); |
| david_s95 | 10:0309d6c49f26 | 284 | position = I1 + 2*I2 + 4*I3; |
| david_s95 | 10:0309d6c49f26 | 285 | printf("position: %d\r\n", position); |
| david_s95 | 10:0309d6c49f26 | 286 | motor=0x0B; |
| david_s95 | 10:0309d6c49f26 | 287 | printf("0x0B\r\n"); |
| david_s95 | 10:0309d6c49f26 | 288 | wait(WAIT); |
| david_s95 | 10:0309d6c49f26 | 289 | position = I1 + 2*I2 + 4*I3; |
| david_s95 | 10:0309d6c49f26 | 290 | printf("position: %d\r\n", position); |
| david_s95 | 10:0309d6c49f26 | 291 | motor=0x23; |
| david_s95 | 10:0309d6c49f26 | 292 | printf("0x23\r\n"); |
| david_s95 | 10:0309d6c49f26 | 293 | wait(WAIT); |
| david_s95 | 10:0309d6c49f26 | 294 | position = I1 + 2*I2 + 4*I3; |
| david_s95 | 10:0309d6c49f26 | 295 | printf("position: %d\r\n", position); |
| david_s95 | 10:0309d6c49f26 | 296 | motor=0x32; |
| david_s95 | 10:0309d6c49f26 | 297 | printf("0x32\r\n"); |
| david_s95 | 10:0309d6c49f26 | 298 | wait(WAIT); |
| david_s95 | 10:0309d6c49f26 | 299 | position = I1 + 2*I2 + 4*I3; |
| david_s95 | 10:0309d6c49f26 | 300 | printf("position: %d\r\n", position); |
| david_s95 | 10:0309d6c49f26 | 301 | }*/ |
| david_s95 | 7:5932ed0bad6d | 302 | |
| estott | 0:de4320f74764 | 303 | //Run the motor synchronisation |
| estott | 2:4e88faab6988 | 304 | orState = motorHome(); |
| david_s95 | 6:4edbe75736d9 | 305 | //orState is subtracted from future rotor state inputs to align rotor and motor states |
| david_s95 | 6:4edbe75736d9 | 306 | |
| estott | 2:4e88faab6988 | 307 | pc.printf("Rotor origin: %x\n\r",orState); |
| david_s95 | 5:e5313b695302 | 308 | |
| david_s95 | 6:4edbe75736d9 | 309 | char command[ARRAYSIZE]; |
| david_s95 | 6:4edbe75736d9 | 310 | int index=0; |
| david_s95 | 6:4edbe75736d9 | 311 | int units = 0, tens = 0, decimals = 0; |
| david_s95 | 6:4edbe75736d9 | 312 | char ch; |
| david_s95 | 9:575b29cbf5e4 | 313 | testpin=0; |
| david_s95 | 7:5932ed0bad6d | 314 | |
| david_s95 | 10:0309d6c49f26 | 315 | speedTimer.reset(); |
| david_s95 | 10:0309d6c49f26 | 316 | speedTimer.start(); |
| david_s95 | 10:0309d6c49f26 | 317 | I2.mode(PullNone); |
| david_s95 | 10:0309d6c49f26 | 318 | I2.fall(&rps); |
| david_s95 | 9:575b29cbf5e4 | 319 | // |
| david_s95 | 9:575b29cbf5e4 | 320 | // qA.rise(&edgeRiseA); |
| david_s95 | 9:575b29cbf5e4 | 321 | // qB.rise(&edgeIncr); |
| david_s95 | 9:575b29cbf5e4 | 322 | // qA.fall(&edgeIncr); |
| david_s95 | 9:575b29cbf5e4 | 323 | // qB.fall(&edgeIncr); |
| david_s95 | 7:5932ed0bad6d | 324 | |
| david_s95 | 10:0309d6c49f26 | 325 | VPIDthread.start(VPID); |
| david_s95 | 10:0309d6c49f26 | 326 | |
| david_s95 | 5:e5313b695302 | 327 | while(1) { |
| david_s95 | 9:575b29cbf5e4 | 328 | // clk = I2; |
| david_s95 | 6:4edbe75736d9 | 329 | //Toggle LED so we know something's happening |
| david_s95 | 8:77627657da80 | 330 | // clk = !clk; |
| david_s95 | 7:5932ed0bad6d | 331 | |
| david_s95 | 6:4edbe75736d9 | 332 | //If there's a character to read from the serial port |
| david_s95 | 6:4edbe75736d9 | 333 | if (pc.readable()) { |
| david_s95 | 7:5932ed0bad6d | 334 | |
| david_s95 | 6:4edbe75736d9 | 335 | //Clear index counter and control variables |
| david_s95 | 6:4edbe75736d9 | 336 | index = 0; |
| david_s95 | 7:5932ed0bad6d | 337 | // revsec = spinWait = 0; |
| david_s95 | 7:5932ed0bad6d | 338 | |
| david_s95 | 6:4edbe75736d9 | 339 | //Read each value from the serial port until Enter key is pressed |
| david_s95 | 6:4edbe75736d9 | 340 | do { |
| david_s95 | 6:4edbe75736d9 | 341 | //Read character |
| david_s95 | 6:4edbe75736d9 | 342 | ch = pc.getc(); |
| david_s95 | 6:4edbe75736d9 | 343 | //Print character to serial for visual feedback |
| david_s95 | 6:4edbe75736d9 | 344 | pc.putc(ch); |
| david_s95 | 6:4edbe75736d9 | 345 | //Add character to input array |
| david_s95 | 6:4edbe75736d9 | 346 | command[index++]=ch; // put it into the value array and increment the index |
| david_s95 | 7:5932ed0bad6d | 347 | //d10 and d13 used for detecting Enter key on Windows/Unix/Mac |
| david_s95 | 6:4edbe75736d9 | 348 | } while(ch != 10 && ch != 13); |
| david_s95 | 7:5932ed0bad6d | 349 | |
| david_s95 | 6:4edbe75736d9 | 350 | //Start new line on terminal for printing data |
| david_s95 | 6:4edbe75736d9 | 351 | pc.putc('\n'); |
| david_s95 | 6:4edbe75736d9 | 352 | pc.putc('\r'); |
| david_s95 | 7:5932ed0bad6d | 353 | |
| david_s95 | 6:4edbe75736d9 | 354 | //Analyse the input string |
| david_s95 | 6:4edbe75736d9 | 355 | switch (command[0]) { |
| david_s95 | 7:5932ed0bad6d | 356 | //If a V was typed... |
| david_s95 | 6:4edbe75736d9 | 357 | case 'V': |
| david_s95 | 7:5932ed0bad6d | 358 | units = 0, tens = 0, decimals = 0; |
| david_s95 | 7:5932ed0bad6d | 359 | //For each character received, subtract ASCII 0 from ASCII |
| david_s95 | 7:5932ed0bad6d | 360 | //representation to obtain the integer value of the number |
| david_s95 | 9:575b29cbf5e4 | 361 | if(command[1]=='-') { |
| david_s95 | 9:575b29cbf5e4 | 362 | spinCW = 0; |
| david_s95 | 9:575b29cbf5e4 | 363 | //If decimal point is in the second character (eg, V-.1) |
| david_s95 | 9:575b29cbf5e4 | 364 | if(command[2]=='.') { |
| david_s95 | 9:575b29cbf5e4 | 365 | //Extract decimal rev/s |
| david_s95 | 9:575b29cbf5e4 | 366 | decimals = command[3] - '0'; |
| david_s95 | 7:5932ed0bad6d | 367 | |
| david_s95 | 9:575b29cbf5e4 | 368 | //If decimal point is in the third character (eg, V-0.1) |
| david_s95 | 9:575b29cbf5e4 | 369 | } else if(command[3]=='.') { |
| david_s95 | 9:575b29cbf5e4 | 370 | units = command[2] - '0'; |
| david_s95 | 9:575b29cbf5e4 | 371 | decimals = command[4] - '0'; |
| david_s95 | 7:5932ed0bad6d | 372 | |
| david_s95 | 9:575b29cbf5e4 | 373 | //If decimal point is in the fourth character (eg, V-10.1) |
| david_s95 | 9:575b29cbf5e4 | 374 | } else if(command[4]=='.') { |
| david_s95 | 9:575b29cbf5e4 | 375 | tens = command[2] - '0'; |
| david_s95 | 9:575b29cbf5e4 | 376 | units = command[3] - '0'; |
| david_s95 | 9:575b29cbf5e4 | 377 | decimals = command[5] - '0'; |
| david_s95 | 9:575b29cbf5e4 | 378 | } |
| david_s95 | 9:575b29cbf5e4 | 379 | } else { |
| david_s95 | 9:575b29cbf5e4 | 380 | spinCW = 1; |
| david_s95 | 9:575b29cbf5e4 | 381 | //If decimal point is in the second character (eg, V.1) |
| david_s95 | 9:575b29cbf5e4 | 382 | if(command[1]=='.') { |
| david_s95 | 9:575b29cbf5e4 | 383 | //Extract decimal rev/s |
| david_s95 | 9:575b29cbf5e4 | 384 | decimals = command[2] - '0'; |
| david_s95 | 7:5932ed0bad6d | 385 | |
| david_s95 | 9:575b29cbf5e4 | 386 | //If decimal point is in the third character (eg, V0.1) |
| david_s95 | 9:575b29cbf5e4 | 387 | } else if(command[2]=='.') { |
| david_s95 | 9:575b29cbf5e4 | 388 | units = command[1] - '0'; |
| david_s95 | 9:575b29cbf5e4 | 389 | decimals = command[3] - '0'; |
| david_s95 | 9:575b29cbf5e4 | 390 | |
| david_s95 | 9:575b29cbf5e4 | 391 | //If decimal point is in the fourth character (eg, V10.1) |
| david_s95 | 9:575b29cbf5e4 | 392 | } else if(command[3]=='.') { |
| david_s95 | 9:575b29cbf5e4 | 393 | tens = command[1] - '0'; |
| david_s95 | 9:575b29cbf5e4 | 394 | units = command[2] - '0'; |
| david_s95 | 9:575b29cbf5e4 | 395 | decimals = command[4] - '0'; |
| david_s95 | 9:575b29cbf5e4 | 396 | } |
| david_s95 | 6:4edbe75736d9 | 397 | } |
| david_s95 | 7:5932ed0bad6d | 398 | |
| david_s95 | 6:4edbe75736d9 | 399 | //Calculate the number of revolutions per second required |
| david_s95 | 6:4edbe75736d9 | 400 | revsec = float(tens)*10 + float(units) + float(decimals)/10; |
| david_s95 | 6:4edbe75736d9 | 401 | //Calculate the required wait period |
| david_s95 | 6:4edbe75736d9 | 402 | spinWait = (1/revsec)/6; |
| david_s95 | 7:5932ed0bad6d | 403 | |
| david_s95 | 6:4edbe75736d9 | 404 | //Print values for verification |
| david_s95 | 7:5932ed0bad6d | 405 | pc.printf("Rev/S: %2.4f, Wait: %2.4f\n\r", revsec, spinWait); |
| david_s95 | 7:5932ed0bad6d | 406 | |
| david_s95 | 6:4edbe75736d9 | 407 | //Run the function to start rotating at a fixed speed |
| david_s95 | 6:4edbe75736d9 | 408 | fixedSpeed(); |
| david_s95 | 6:4edbe75736d9 | 409 | break; |
| david_s95 | 7:5932ed0bad6d | 410 | //If anything unexpected was received |
| david_s95 | 7:5932ed0bad6d | 411 | case 's': |
| david_s95 | 9:575b29cbf5e4 | 412 | // pc.printf("Revs / sec: %2.2f\r", revs); |
| david_s95 | 9:575b29cbf5e4 | 413 | // printSpeed.attach(&speedo, 1.0); |
| david_s95 | 10:0309d6c49f26 | 414 | printf("Measured: %2.3f, revsec: %2.3f\r\n", measuredRevs, revsec); |
| david_s95 | 10:0309d6c49f26 | 415 | printf("speed setpoint: %2.3f\r\n", speedControl); |
| david_s95 | 7:5932ed0bad6d | 416 | break; |
| david_s95 | 8:77627657da80 | 417 | case 't': |
| david_s95 | 10:0309d6c49f26 | 418 | // pc.printf("%d\n\r", pos); |
| david_s95 | 8:77627657da80 | 419 | break; |
| david_s95 | 6:4edbe75736d9 | 420 | default: |
| david_s95 | 6:4edbe75736d9 | 421 | //Set speed variables to zero to stop motor spinning |
| david_s95 | 6:4edbe75736d9 | 422 | //Print error message |
| david_s95 | 10:0309d6c49f26 | 423 | motorStop(); |
| david_s95 | 10:0309d6c49f26 | 424 | pc.printf("Error in received data 0\n\r"); |
| david_s95 | 6:4edbe75736d9 | 425 | break; |
| david_s95 | 6:4edbe75736d9 | 426 | } |
| david_s95 | 6:4edbe75736d9 | 427 | } |
| david_s95 | 7:5932ed0bad6d | 428 | // printSpeed.attach(&speedo, 1.0); |
| david_s95 | 7:5932ed0bad6d | 429 | // pc.printf("Revs / sec: %2.2f\r", revs); |
| estott | 2:4e88faab6988 | 430 | } |
| david_s95 | 5:e5313b695302 | 431 | |
| estott | 0:de4320f74764 | 432 | } |
