Callum and Adel's changes on 12/02/19
Dependencies: Crypto
main.cpp@27:ce05fed3c1ea, 2019-03-16 (annotated)
- Committer:
- adehadd
- Date:
- Sat Mar 16 18:25:38 2019 +0000
- Revision:
- 27:ce05fed3c1ea
- Parent:
- 26:fb6151e5907d
- Child:
- 42:121148278dae
oh dear
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
adehadd | 27:ce05fed3c1ea | 1 | #include "SHA256.h" |
estott | 0:de4320f74764 | 2 | #include "mbed.h" |
adehadd | 27:ce05fed3c1ea | 3 | // #include <iostream> |
adehadd | 27:ce05fed3c1ea | 4 | // #include "rtos.h" |
CallumAlder | 14:4e312fb83330 | 5 | |
adehadd | 27:ce05fed3c1ea | 6 | /*TODO: |
adehadd | 27:ce05fed3c1ea | 7 | Change |
adehadd | 27:ce05fed3c1ea | 8 | Indx |
adehadd | 27:ce05fed3c1ea | 9 | newCmd |
adehadd | 27:ce05fed3c1ea | 10 | MAXCMDLENGTH |
adehadd | 27:ce05fed3c1ea | 11 | */ |
estott | 0:de4320f74764 | 12 | |
adehadd | 27:ce05fed3c1ea | 13 | //Photointerrupter input pins |
adehadd | 27:ce05fed3c1ea | 14 | #define I1pin D3 |
adehadd | 27:ce05fed3c1ea | 15 | #define I2pin D6 |
adehadd | 27:ce05fed3c1ea | 16 | #define I3pin D5 |
estott | 2:4e88faab6988 | 17 | |
adehadd | 27:ce05fed3c1ea | 18 | //Incremental encoder input pins |
adehadd | 27:ce05fed3c1ea | 19 | #define CHApin D12 |
adehadd | 27:ce05fed3c1ea | 20 | #define CHBpin D11 |
estott | 0:de4320f74764 | 21 | |
adehadd | 27:ce05fed3c1ea | 22 | //Motor Drive output pins //Mask in output byte |
adehadd | 27:ce05fed3c1ea | 23 | #define L1Lpin D1 //0x01 |
adehadd | 27:ce05fed3c1ea | 24 | #define L1Hpin A3 //0x02 |
adehadd | 27:ce05fed3c1ea | 25 | #define L2Lpin D0 //0x04 |
adehadd | 27:ce05fed3c1ea | 26 | #define L2Hpin A6 //0x08 |
adehadd | 27:ce05fed3c1ea | 27 | #define L3Lpin D10 //0x10 |
adehadd | 27:ce05fed3c1ea | 28 | #define L3Hpin D2 //0x20 |
estott | 10:a4b5723b6c9d | 29 | |
adehadd | 27:ce05fed3c1ea | 30 | #define PWMpin D9 |
estott | 5:08f338b5e4d9 | 31 | |
adehadd | 27:ce05fed3c1ea | 32 | //Motor current sense |
adehadd | 27:ce05fed3c1ea | 33 | #define MCSPpin A1 |
adehadd | 27:ce05fed3c1ea | 34 | #define MCSNpin A0 |
estott | 0:de4320f74764 | 35 | |
estott | 0:de4320f74764 | 36 | //Mapping from sequential drive states to motor phase outputs |
estott | 0:de4320f74764 | 37 | /* |
estott | 0:de4320f74764 | 38 | State L1 L2 L3 |
estott | 0:de4320f74764 | 39 | 0 H - L |
estott | 0:de4320f74764 | 40 | 1 - H L |
estott | 0:de4320f74764 | 41 | 2 L H - |
estott | 0:de4320f74764 | 42 | 3 L - H |
estott | 0:de4320f74764 | 43 | 4 - L H |
estott | 0:de4320f74764 | 44 | 5 H L - |
estott | 0:de4320f74764 | 45 | 6 - - - |
estott | 0:de4320f74764 | 46 | 7 - - - |
estott | 0:de4320f74764 | 47 | */ |
adehadd | 27:ce05fed3c1ea | 48 | //Drive state to output table |
estott | 0:de4320f74764 | 49 | const int8_t driveTable[] = {0x12,0x18,0x09,0x21,0x24,0x06,0x00,0x00}; |
estott | 2:4e88faab6988 | 50 | |
adehadd | 27:ce05fed3c1ea | 51 | //Mapping from interrupter inputs to sequential rotor states. 0x00 and 0x07 are not valid |
adehadd | 27:ce05fed3c1ea | 52 | const int8_t stateMap[] = {0x07,0x05,0x03,0x04,0x01,0x00,0x02,0x07}; |
adehadd | 27:ce05fed3c1ea | 53 | //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 | 54 | |
adehadd | 27:ce05fed3c1ea | 55 | //Phase lead to make motor spin |
adehadd | 27:ce05fed3c1ea | 56 | const int8_t lead = 2; //2 for forwards, -2 for backwards |
estott | 0:de4320f74764 | 57 | |
adehadd | 27:ce05fed3c1ea | 58 | //Status LED |
estott | 0:de4320f74764 | 59 | DigitalOut led1(LED1); |
estott | 0:de4320f74764 | 60 | |
adehadd | 27:ce05fed3c1ea | 61 | //Photointerrupter inputs |
iachinweze1 | 12:41b3112021a3 | 62 | InterruptIn I1(I1pin); |
iachinweze1 | 12:41b3112021a3 | 63 | InterruptIn I2(I2pin); |
iachinweze1 | 12:41b3112021a3 | 64 | InterruptIn I3(I3pin); |
estott | 0:de4320f74764 | 65 | |
adehadd | 27:ce05fed3c1ea | 66 | //Motor Drive outputs |
adehadd | 27:ce05fed3c1ea | 67 | DigitalOut L1L(L1Lpin); |
estott | 0:de4320f74764 | 68 | DigitalOut L1H(L1Hpin); |
adehadd | 27:ce05fed3c1ea | 69 | DigitalOut L2L(L2Lpin); |
estott | 0:de4320f74764 | 70 | DigitalOut L2H(L2Hpin); |
adehadd | 27:ce05fed3c1ea | 71 | DigitalOut L3L(L3Lpin); |
estott | 0:de4320f74764 | 72 | DigitalOut L3H(L3Hpin); |
estott | 0:de4320f74764 | 73 | |
adehadd | 27:ce05fed3c1ea | 74 | PwmOut pwmCtrl(PWMpin); |
iachinweze1 | 23:ab1cb51527d1 | 75 | |
adehadd | 27:ce05fed3c1ea | 76 | uint8_t stateCount[3]; |
adehadd | 27:ce05fed3c1ea | 77 | uint8_t theStates[3]; |
adehadd | 27:ce05fed3c1ea | 78 | |
adehadd | 27:ce05fed3c1ea | 79 | class Comm /*: public T_*/{ |
adehadd | 27:ce05fed3c1ea | 80 | |
adehadd | 27:ce05fed3c1ea | 81 | public: |
adehadd | 27:ce05fed3c1ea | 82 | |
adehadd | 27:ce05fed3c1ea | 83 | Thread t_comm_out; |
adehadd | 27:ce05fed3c1ea | 84 | Thread t_motor_ctrl; |
adehadd | 27:ce05fed3c1ea | 85 | // Thread *p_motor_ctrl; |
adehadd | 27:ce05fed3c1ea | 86 | |
adehadd | 27:ce05fed3c1ea | 87 | bool _RUN; |
adehadd | 27:ce05fed3c1ea | 88 | |
adehadd | 27:ce05fed3c1ea | 89 | RawSerial pc; |
adehadd | 27:ce05fed3c1ea | 90 | // Queue<void, 8> inCharQ; // Input Character Queue |
iachinweze1 | 23:ab1cb51527d1 | 91 | |
iachinweze1 | 23:ab1cb51527d1 | 92 | |
adehadd | 27:ce05fed3c1ea | 93 | static const char MsgChar[11]; |
adehadd | 27:ce05fed3c1ea | 94 | |
adehadd | 27:ce05fed3c1ea | 95 | uint8_t MAXCMDLENGTH; |
iachinweze1 | 23:ab1cb51527d1 | 96 | |
adehadd | 27:ce05fed3c1ea | 97 | volatile uint8_t cmdIndx; |
adehadd | 27:ce05fed3c1ea | 98 | volatile uint8_t inCharQIdx; |
adehadd | 27:ce05fed3c1ea | 99 | |
adehadd | 27:ce05fed3c1ea | 100 | volatile uint32_t motorPower; // motor toque |
adehadd | 27:ce05fed3c1ea | 101 | volatile float targetVel; |
adehadd | 27:ce05fed3c1ea | 102 | volatile float targetRot; |
adehadd | 27:ce05fed3c1ea | 103 | |
adehadd | 27:ce05fed3c1ea | 104 | enum msgType {motorState, posIn, velIn, posOut, velOut, |
iachinweze1 | 23:ab1cb51527d1 | 105 | |
adehadd | 27:ce05fed3c1ea | 106 | hashRate, keyAdded, nonceMatch, |
adehadd | 27:ce05fed3c1ea | 107 | |
adehadd | 27:ce05fed3c1ea | 108 | torque, rotations, |
adehadd | 27:ce05fed3c1ea | 109 | |
adehadd | 27:ce05fed3c1ea | 110 | error}; |
iachinweze1 | 23:ab1cb51527d1 | 111 | |
adehadd | 27:ce05fed3c1ea | 112 | typedef struct { |
adehadd | 27:ce05fed3c1ea | 113 | msgType type; |
adehadd | 27:ce05fed3c1ea | 114 | uint32_t message; |
adehadd | 27:ce05fed3c1ea | 115 | } msg; |
adehadd | 27:ce05fed3c1ea | 116 | |
adehadd | 27:ce05fed3c1ea | 117 | Mail<msg, 32> mailStack; |
iachinweze1 | 23:ab1cb51527d1 | 118 | |
adehadd | 27:ce05fed3c1ea | 119 | void serialISR(){ |
adehadd | 27:ce05fed3c1ea | 120 | if (pc.readable()) { |
adehadd | 27:ce05fed3c1ea | 121 | char newChar = pc.getc(); |
adehadd | 27:ce05fed3c1ea | 122 | // inCharQ.put((void*)newChar); // void* = pointer to an unknown type that cannot be dereferenced |
CallumAlder | 19:805c87360b55 | 123 | |
adehadd | 27:ce05fed3c1ea | 124 | if (inCharQIdx == (MAXCMDLENGTH)) { |
adehadd | 27:ce05fed3c1ea | 125 | inCharQ[MAXCMDLENGTH] = '\0'; // force the string to have an end character |
adehadd | 27:ce05fed3c1ea | 126 | putMessage(error, 1); |
adehadd | 27:ce05fed3c1ea | 127 | inCharQIdx = 0; // reset buffer index |
adehadd | 27:ce05fed3c1ea | 128 | // pc.putc('\r'); // carriage return moves to the start of the line |
adehadd | 27:ce05fed3c1ea | 129 | // for (int i = 0; i < MAXCMDLENGTH; ++i) |
adehadd | 27:ce05fed3c1ea | 130 | // { |
adehadd | 27:ce05fed3c1ea | 131 | // inCharQ[i] = ' '; |
adehadd | 27:ce05fed3c1ea | 132 | // pc.putc(' '); |
adehadd | 27:ce05fed3c1ea | 133 | // } |
iachinweze1 | 23:ab1cb51527d1 | 134 | |
adehadd | 27:ce05fed3c1ea | 135 | // pc.putc('\r'); // carriage return moves to the start of the line |
adehadd | 27:ce05fed3c1ea | 136 | } |
adehadd | 27:ce05fed3c1ea | 137 | else{ |
adehadd | 27:ce05fed3c1ea | 138 | if(newChar != '\r'){ //While the command is not over, |
adehadd | 27:ce05fed3c1ea | 139 | inCharQ[inCharQIdx] = newChar; //save input character and |
adehadd | 27:ce05fed3c1ea | 140 | inCharQIdx++; //advance index |
adehadd | 27:ce05fed3c1ea | 141 | pc.putc(newChar); |
adehadd | 27:ce05fed3c1ea | 142 | } |
adehadd | 27:ce05fed3c1ea | 143 | else{ |
adehadd | 27:ce05fed3c1ea | 144 | inCharQ[inCharQIdx] = '\0'; //When the command is finally over, |
adehadd | 27:ce05fed3c1ea | 145 | strncpy(newCmd, inCharQ, MAXCMDLENGTH); // Will copy 18 characters from inCharQ to newCmd |
adehadd | 27:ce05fed3c1ea | 146 | cmdParser(); //parse the command for decoding. |
adehadd | 27:ce05fed3c1ea | 147 | for (int i = 0; i < MAXCMDLENGTH; ++i) // reset buffer |
adehadd | 27:ce05fed3c1ea | 148 | inCharQ[i] = ' '; |
adehadd | 27:ce05fed3c1ea | 149 | inCharQIdx = 0; // reset index |
adehadd | 27:ce05fed3c1ea | 150 | } |
adehadd | 27:ce05fed3c1ea | 151 | } |
adehadd | 27:ce05fed3c1ea | 152 | } |
CallumAlder | 19:805c87360b55 | 153 | |
iachinweze1 | 23:ab1cb51527d1 | 154 | |
adehadd | 27:ce05fed3c1ea | 155 | } |
adehadd | 27:ce05fed3c1ea | 156 | |
adehadd | 27:ce05fed3c1ea | 157 | /*void commInFn() { |
adehadd | 27:ce05fed3c1ea | 158 | // if (_RUN) |
iachinweze1 | 23:ab1cb51527d1 | 159 | |
adehadd | 27:ce05fed3c1ea | 160 | while (_RUN) { |
adehadd | 27:ce05fed3c1ea | 161 | osEvent newEvent = inCharQ.get(); |
adehadd | 27:ce05fed3c1ea | 162 | uint8_t newChar = (uint8_t)(newEvent.value.p); // size_t to type cast the 64bit pointer properly |
adehadd | 27:ce05fed3c1ea | 163 | pc.putc(newChar); |
adehadd | 27:ce05fed3c1ea | 164 | if(cmdIndx >= MAXCMDLENGTH){ //Make sure there is no overflow in comand. |
adehadd | 27:ce05fed3c1ea | 165 | cmdIndx = 0; |
adehadd | 27:ce05fed3c1ea | 166 | putMessage(error, 1); |
adehadd | 27:ce05fed3c1ea | 167 | } |
adehadd | 27:ce05fed3c1ea | 168 | else{ |
adehadd | 27:ce05fed3c1ea | 169 | if(newChar != '\r'){ //While the command is not over, |
adehadd | 27:ce05fed3c1ea | 170 | newCmd[cmdIndx] = newChar; //save input character and |
adehadd | 27:ce05fed3c1ea | 171 | cmdIndx++; //advance index |
adehadd | 27:ce05fed3c1ea | 172 | } |
adehadd | 27:ce05fed3c1ea | 173 | else{ |
adehadd | 27:ce05fed3c1ea | 174 | newCmd[cmdIndx] = '\0'; //When the command is finally over, |
adehadd | 27:ce05fed3c1ea | 175 | cmdIndx = 0; //reset index and |
adehadd | 27:ce05fed3c1ea | 176 | cmdParser(); //parse the command for decoding. |
adehadd | 27:ce05fed3c1ea | 177 | } |
adehadd | 27:ce05fed3c1ea | 178 | } |
adehadd | 27:ce05fed3c1ea | 179 | } |
adehadd | 27:ce05fed3c1ea | 180 | }*/ |
iachinweze1 | 23:ab1cb51527d1 | 181 | |
adehadd | 27:ce05fed3c1ea | 182 | void returnCursor() { |
adehadd | 27:ce05fed3c1ea | 183 | pc.putc('>'); |
adehadd | 27:ce05fed3c1ea | 184 | for (int i = 0; i < inCharQIdx; ++i) // reset cursor position |
adehadd | 27:ce05fed3c1ea | 185 | pc.putc(inCharQ[i]); |
adehadd | 27:ce05fed3c1ea | 186 | // for (int i = inCharQIdx; i < MAXCMDLENGTH; ++i) // fill remaining with blanks |
adehadd | 27:ce05fed3c1ea | 187 | // pc.putc(' '); |
adehadd | 27:ce05fed3c1ea | 188 | // pc.putc('<'); |
adehadd | 27:ce05fed3c1ea | 189 | } |
iachinweze1 | 23:ab1cb51527d1 | 190 | |
adehadd | 27:ce05fed3c1ea | 191 | void cmdParser(){ |
adehadd | 27:ce05fed3c1ea | 192 | switch(newCmd[0]) { |
adehadd | 27:ce05fed3c1ea | 193 | case 'K': //(MsgChar[keyAdded]):// |
adehadd | 27:ce05fed3c1ea | 194 | newKey_mutex.lock(); //Ensure there is no deadlock |
adehadd | 27:ce05fed3c1ea | 195 | sscanf(newCmd, "K%x", &newKey); //Find desired the Key code |
adehadd | 27:ce05fed3c1ea | 196 | putMessage(keyAdded, newKey); //Print it out |
adehadd | 27:ce05fed3c1ea | 197 | newKey_mutex.unlock(); |
adehadd | 27:ce05fed3c1ea | 198 | break; |
adehadd | 27:ce05fed3c1ea | 199 | case 'V': //(MsgChar[velIn]):// |
adehadd | 27:ce05fed3c1ea | 200 | sscanf(newCmd, "V%f", &targetVel); //Find desired the target velocity |
adehadd | 27:ce05fed3c1ea | 201 | putMessage(velIn, targetVel); //Print it out |
adehadd | 27:ce05fed3c1ea | 202 | break; |
adehadd | 27:ce05fed3c1ea | 203 | case 'R': //(MsgChar[posIn]):// |
adehadd | 27:ce05fed3c1ea | 204 | sscanf(newCmd, "R%f", &targetRot); //Find desired target rotation |
adehadd | 27:ce05fed3c1ea | 205 | putMessage(posIn, targetRot); //Print it out |
adehadd | 27:ce05fed3c1ea | 206 | break; |
adehadd | 27:ce05fed3c1ea | 207 | case 'T': //(MsgChar[torque]):// |
adehadd | 27:ce05fed3c1ea | 208 | sscanf(newCmd, "T%d", &motorPower); //Find desired target torque |
adehadd | 27:ce05fed3c1ea | 209 | putMessage(torque, motorPower); //Print it out |
adehadd | 27:ce05fed3c1ea | 210 | break; |
adehadd | 27:ce05fed3c1ea | 211 | default: break; |
adehadd | 27:ce05fed3c1ea | 212 | } |
adehadd | 27:ce05fed3c1ea | 213 | } |
adehadd | 27:ce05fed3c1ea | 214 | |
adehadd | 27:ce05fed3c1ea | 215 | //~~~~~Decode messages to print on serial port~~~~~ |
adehadd | 27:ce05fed3c1ea | 216 | void commOutFn() { |
adehadd | 27:ce05fed3c1ea | 217 | while (_RUN) { |
adehadd | 27:ce05fed3c1ea | 218 | osEvent newEvent = mailStack.get(); |
adehadd | 27:ce05fed3c1ea | 219 | msg *pMessage = (msg *) newEvent.value.p; |
iachinweze1 | 23:ab1cb51527d1 | 220 | |
adehadd | 27:ce05fed3c1ea | 221 | //Case switch to choose serial output based on incoming message |
adehadd | 27:ce05fed3c1ea | 222 | switch (pMessage->type) { |
adehadd | 27:ce05fed3c1ea | 223 | case motorState: |
adehadd | 27:ce05fed3c1ea | 224 | pc.printf("The motor is currently in state %x\n\r", pMessage->message); |
adehadd | 27:ce05fed3c1ea | 225 | break; |
adehadd | 27:ce05fed3c1ea | 226 | case hashRate: |
adehadd | 27:ce05fed3c1ea | 227 | pc.printf("\r>%s< Mining: %.4u Hash/s\r", inCharQ, (uint32_t) pMessage->message); |
adehadd | 27:ce05fed3c1ea | 228 | returnCursor(); |
adehadd | 27:ce05fed3c1ea | 229 | break; |
adehadd | 27:ce05fed3c1ea | 230 | case nonceMatch: |
adehadd | 27:ce05fed3c1ea | 231 | pc.printf("\r>%s< Nonce found: %x\r", inCharQ, pMessage->message); |
adehadd | 27:ce05fed3c1ea | 232 | returnCursor(); |
adehadd | 27:ce05fed3c1ea | 233 | break; |
adehadd | 27:ce05fed3c1ea | 234 | case keyAdded: |
adehadd | 27:ce05fed3c1ea | 235 | pc.printf("New Key Added:\t0x%016x\n\r", pMessage->message); |
adehadd | 27:ce05fed3c1ea | 236 | break; |
adehadd | 27:ce05fed3c1ea | 237 | case torque: |
adehadd | 27:ce05fed3c1ea | 238 | pc.printf("Motor Torque set to:\t%d\n\r", pMessage->message); |
adehadd | 27:ce05fed3c1ea | 239 | break; |
adehadd | 27:ce05fed3c1ea | 240 | case velIn: |
adehadd | 27:ce05fed3c1ea | 241 | pc.printf("Target Velocity set to:\t%.2f\n\r", targetVel); |
adehadd | 27:ce05fed3c1ea | 242 | break; |
adehadd | 27:ce05fed3c1ea | 243 | case velOut: |
adehadd | 27:ce05fed3c1ea | 244 | pc.printf("Current Velocity:\t%.2f\n\r", \ |
adehadd | 27:ce05fed3c1ea | 245 | (float) ((int32_t) pMessage->message / 6)); |
adehadd | 27:ce05fed3c1ea | 246 | break; |
adehadd | 27:ce05fed3c1ea | 247 | case posIn: |
adehadd | 27:ce05fed3c1ea | 248 | pc.printf("Target Rotation set to:\t%.2f\n\r", \ |
adehadd | 27:ce05fed3c1ea | 249 | (float) ((int32_t) pMessage->message / 6)); |
adehadd | 27:ce05fed3c1ea | 250 | break; |
adehadd | 27:ce05fed3c1ea | 251 | case posOut: |
adehadd | 27:ce05fed3c1ea | 252 | pc.printf("Current Position:\t%.2f\n\r", \ |
adehadd | 27:ce05fed3c1ea | 253 | (float) ((int32_t) pMessage->message / 6)); |
adehadd | 27:ce05fed3c1ea | 254 | break; |
adehadd | 27:ce05fed3c1ea | 255 | case error: |
adehadd | 27:ce05fed3c1ea | 256 | pc.printf("\r>%s< Debugging position:%x\n\r", inCharQ, pMessage->message); |
adehadd | 27:ce05fed3c1ea | 257 | for (int i = 0; i < MAXCMDLENGTH; ++i) // reset buffer |
adehadd | 27:ce05fed3c1ea | 258 | inCharQ[i] = ' '; |
adehadd | 27:ce05fed3c1ea | 259 | break; |
adehadd | 27:ce05fed3c1ea | 260 | default: |
adehadd | 27:ce05fed3c1ea | 261 | pc.printf("Unknown Error. Message: %x\n\r", pMessage->message); |
adehadd | 27:ce05fed3c1ea | 262 | break; |
adehadd | 27:ce05fed3c1ea | 263 | } |
adehadd | 27:ce05fed3c1ea | 264 | mailStack.free(pMessage); |
adehadd | 27:ce05fed3c1ea | 265 | } |
adehadd | 27:ce05fed3c1ea | 266 | } |
adehadd | 26:fb6151e5907d | 267 | |
adehadd | 27:ce05fed3c1ea | 268 | // attach_us -> runs funtion every 100ms |
adehadd | 27:ce05fed3c1ea | 269 | void motorCtrlFn() { |
adehadd | 27:ce05fed3c1ea | 270 | Ticker motorCtrlTicker; |
adehadd | 27:ce05fed3c1ea | 271 | motorCtrlTicker.attach_us(callback(this,&Comm::motorCtrlTick), 1e5); |
adehadd | 27:ce05fed3c1ea | 272 | uint8_t cpyStateCount[3]; |
adehadd | 27:ce05fed3c1ea | 273 | uint8_t cpyCurrentState; |
adehadd | 27:ce05fed3c1ea | 274 | |
adehadd | 27:ce05fed3c1ea | 275 | int16_t ting[2] = {5,1}; // 360,60 (for degrees), 5,1 (for states) |
adehadd | 27:ce05fed3c1ea | 276 | uint8_t iterElementMax; |
adehadd | 27:ce05fed3c1ea | 277 | int16_t totalDegrees; |
adehadd | 27:ce05fed3c1ea | 278 | int16_t stateDiff; |
adehadd | 27:ce05fed3c1ea | 279 | |
adehadd | 27:ce05fed3c1ea | 280 | int32_t velocity; //Variable for local velocity calculation |
adehadd | 27:ce05fed3c1ea | 281 | int32_t locMotorPos; //Local copy of motor position |
adehadd | 27:ce05fed3c1ea | 282 | static int32_t oldMotorPos = 0; //Old motor position used for calculations |
adehadd | 27:ce05fed3c1ea | 283 | static uint8_t motorCtrlCounter = 0; //Counter to be reset every 10 iterations to get velocity calculation in seconds |
adehadd | 27:ce05fed3c1ea | 284 | int32_t torque; //Local variable to set motor torque |
adehadd | 27:ce05fed3c1ea | 285 | float sError; //Velocity error between target and reality |
adehadd | 27:ce05fed3c1ea | 286 | float rError; //Rotation error between target and reality |
adehadd | 27:ce05fed3c1ea | 287 | static float rErrorOld; //Old rotation error used for calculation |
adehadd | 20:c60f4785b556 | 288 | |
adehadd | 27:ce05fed3c1ea | 289 | //~~~Controller constants~~~~ |
adehadd | 27:ce05fed3c1ea | 290 | int32_t Kp1=22; //Proportional controller constants |
adehadd | 27:ce05fed3c1ea | 291 | int32_t Kp2=22; //Calculated by trial and error to give optimal accuracy |
adehadd | 27:ce05fed3c1ea | 292 | float Kd=15.5; |
adehadd | 27:ce05fed3c1ea | 293 | |
adehadd | 27:ce05fed3c1ea | 294 | |
adehadd | 27:ce05fed3c1ea | 295 | while (_RUN) { |
adehadd | 27:ce05fed3c1ea | 296 | t_motor_ctrl.signal_wait((int32_t)0x1); |
adehadd | 27:ce05fed3c1ea | 297 | core_util_critical_section_enter(); |
adehadd | 27:ce05fed3c1ea | 298 | //Access shared variables here |
adehadd | 27:ce05fed3c1ea | 299 | std::copy(stateCount, stateCount+3, cpyStateCount); |
adehadd | 27:ce05fed3c1ea | 300 | // TODO: A thing yes |
adehadd | 27:ce05fed3c1ea | 301 | cpyCurrentState = 0; |
adehadd | 27:ce05fed3c1ea | 302 | for (int i = 0; i < 3; ++i) { |
adehadd | 27:ce05fed3c1ea | 303 | stateCount[i] = 0; |
adehadd | 27:ce05fed3c1ea | 304 | } |
adehadd | 27:ce05fed3c1ea | 305 | core_util_critical_section_exit(); |
adehadd | 27:ce05fed3c1ea | 306 | |
adehadd | 27:ce05fed3c1ea | 307 | iterElementMax = std::max_element(cpyStateCount, cpyStateCount+3) - cpyStateCount; |
adehadd | 27:ce05fed3c1ea | 308 | |
adehadd | 27:ce05fed3c1ea | 309 | |
adehadd | 27:ce05fed3c1ea | 310 | totalDegrees = ting[0] * cpyStateCount[iterElementMax]; |
adehadd | 27:ce05fed3c1ea | 311 | stateDiff = theStates[iterElementMax]-cpyCurrentState; |
adehadd | 27:ce05fed3c1ea | 312 | if (stateDiff >= 0) { |
adehadd | 27:ce05fed3c1ea | 313 | totalDegrees = totalDegrees + (ting[1]* stateDiff); |
adehadd | 27:ce05fed3c1ea | 314 | } else { |
adehadd | 27:ce05fed3c1ea | 315 | totalDegrees = totalDegrees + (ting[1]*stateDiff*-1); |
adehadd | 27:ce05fed3c1ea | 316 | } |
adehadd | 27:ce05fed3c1ea | 317 | pc.printf("%u,%u,%u,%u. %.6i \r", iterElementMax, cpyStateCount[0],cpyStateCount[1],cpyStateCount[2], (totalDegrees*10)); |
adehadd | 27:ce05fed3c1ea | 318 | |
adehadd | 27:ce05fed3c1ea | 319 | /* |
adehadd | 27:ce05fed3c1ea | 320 | //~~~~~Speed controller~~~~~~ |
adehadd | 27:ce05fed3c1ea | 321 | velocity = totalDegrees*10; |
adehadd | 27:ce05fed3c1ea | 322 | sError = (targetVel * 6) - abs(velocity); //Read global variable targetVel updated by interrupt and calculate error between target and reality |
adehadd | 27:ce05fed3c1ea | 323 | int32_t Ys; //Initialise controller output Ys (s=speed) |
adehadd | 27:ce05fed3c1ea | 324 | if (sError == -abs(velocity)) { //Check if user entered V0, |
adehadd | 27:ce05fed3c1ea | 325 | Ys = MAXPWM; //and set the output to maximum as specified |
adehadd | 27:ce05fed3c1ea | 326 | } else { |
adehadd | 27:ce05fed3c1ea | 327 | Ys = (int)(Kp1 * sError); //If the user didn't enter V0 implement controller transfer function: Ys = Kp * (s -|v|) where, |
adehadd | 27:ce05fed3c1ea | 328 | } //Ys = controller output, Kp = prop controller constant, s = target velocity and v is the measured velocity |
adehadd | 27:ce05fed3c1ea | 329 | |
adehadd | 27:ce05fed3c1ea | 330 | //~~~~~Rotation control~~~~~~ |
adehadd | 27:ce05fed3c1ea | 331 | rError = targetRot - (locMotorPos/6); //Read global variable targetRot updated by interrupt and calculate the rotation error. |
adehadd | 27:ce05fed3c1ea | 332 | int32_t Yr; //Initialise controller output Yr (r=rotations) |
adehadd | 27:ce05fed3c1ea | 333 | Yr = Kp2*rError + Kd*(rError - rErrorOld); //Implement controller transfer function Ys= Kp*Er + Kd* (dEr/dt) |
adehadd | 27:ce05fed3c1ea | 334 | rErrorOld = rError; //Update rotation error |
adehadd | 27:ce05fed3c1ea | 335 | if(rError < 0){ //Use the sign of the error to set controller wrt direction of rotation |
adehadd | 27:ce05fed3c1ea | 336 | Ys = -Ys; |
adehadd | 27:ce05fed3c1ea | 337 | } |
adehadd | 27:ce05fed3c1ea | 338 | |
adehadd | 27:ce05fed3c1ea | 339 | if((velocity>=0 && Ys<Yr) || (velocity<0 && Ys>Yr)){ //Choose Ys or Yr based on distance from target value so that it takes |
adehadd | 27:ce05fed3c1ea | 340 | torque = Ys; //appropriate steps in the right direction to reach target value |
adehadd | 27:ce05fed3c1ea | 341 | } else { |
adehadd | 27:ce05fed3c1ea | 342 | torque = Yr; |
adehadd | 27:ce05fed3c1ea | 343 | } |
adehadd | 27:ce05fed3c1ea | 344 | if(torque < 0){ //Variable torque cannot be negative since it sets the PWM |
adehadd | 27:ce05fed3c1ea | 345 | torque = -torque; //Hence we make the value positive, |
adehadd | 27:ce05fed3c1ea | 346 | lead = -2; //and instead set the direction to the opposite one |
adehadd | 27:ce05fed3c1ea | 347 | } else { |
adehadd | 27:ce05fed3c1ea | 348 | lead = 2; |
adehadd | 27:ce05fed3c1ea | 349 | } |
adehadd | 27:ce05fed3c1ea | 350 | if(torque > MAXPWM){ //In case the calculated PWM is higher than our maximum 50% allowance, |
adehadd | 27:ce05fed3c1ea | 351 | torque = MAXPWM; //Set it to our max. |
adehadd | 27:ce05fed3c1ea | 352 | } |
adehadd | 27:ce05fed3c1ea | 353 | |
adehadd | 27:ce05fed3c1ea | 354 | motorPower = torque; //Lastly, update global variable motorPower which is updated by interrupt |
adehadd | 27:ce05fed3c1ea | 355 | */ |
adehadd | 27:ce05fed3c1ea | 356 | } |
adehadd | 27:ce05fed3c1ea | 357 | |
adehadd | 27:ce05fed3c1ea | 358 | } |
adehadd | 27:ce05fed3c1ea | 359 | |
adehadd | 27:ce05fed3c1ea | 360 | void motorCtrlTick(){ |
adehadd | 27:ce05fed3c1ea | 361 | t_motor_ctrl.signal_set(0x1); |
adehadd | 27:ce05fed3c1ea | 362 | } |
adehadd | 20:c60f4785b556 | 363 | |
adehadd | 20:c60f4785b556 | 364 | |
adehadd | 27:ce05fed3c1ea | 365 | //TODO: stop function, maybe use parent de-constructor |
adehadd | 27:ce05fed3c1ea | 366 | //void stop_comm{} |
iachinweze1 | 23:ab1cb51527d1 | 367 | |
adehadd | 27:ce05fed3c1ea | 368 | // public: |
adehadd | 27:ce05fed3c1ea | 369 | |
adehadd | 27:ce05fed3c1ea | 370 | volatile uint64_t newKey; // hash key |
adehadd | 27:ce05fed3c1ea | 371 | Mutex newKey_mutex; // Restrict access to prevent deadlock. |
adehadd | 20:c60f4785b556 | 372 | |
adehadd | 27:ce05fed3c1ea | 373 | Comm() : pc(SERIAL_TX, SERIAL_RX), |
adehadd | 27:ce05fed3c1ea | 374 | t_comm_out(osPriorityAboveNormal, 1024), |
adehadd | 27:ce05fed3c1ea | 375 | t_motor_ctrl(osPriorityAboveNormal2, 1024) |
adehadd | 27:ce05fed3c1ea | 376 | { // inherit from the RawSerial constructor |
adehadd | 27:ce05fed3c1ea | 377 | |
adehadd | 27:ce05fed3c1ea | 378 | pc.printf("%s\n\r", "Welcome" ); |
adehadd | 27:ce05fed3c1ea | 379 | MAXCMDLENGTH = 18; |
adehadd | 20:c60f4785b556 | 380 | |
adehadd | 27:ce05fed3c1ea | 381 | // reset buffer |
adehadd | 27:ce05fed3c1ea | 382 | // MbedOS prints 'Embedded Systems are fun and do awesome things!' |
adehadd | 27:ce05fed3c1ea | 383 | // if you print a null terminator |
adehadd | 27:ce05fed3c1ea | 384 | pc.putc('>'); |
adehadd | 27:ce05fed3c1ea | 385 | for (int i = 0; i < MAXCMDLENGTH; ++i) { |
adehadd | 27:ce05fed3c1ea | 386 | inCharQ[i] = '.'; |
adehadd | 27:ce05fed3c1ea | 387 | pc.putc('.'); |
adehadd | 27:ce05fed3c1ea | 388 | } |
adehadd | 27:ce05fed3c1ea | 389 | pc.putc('<'); |
adehadd | 27:ce05fed3c1ea | 390 | pc.putc('\r'); |
iachinweze1 | 23:ab1cb51527d1 | 391 | |
adehadd | 27:ce05fed3c1ea | 392 | inCharQ[MAXCMDLENGTH] = '\0'; |
adehadd | 27:ce05fed3c1ea | 393 | strncpy(newCmd, inCharQ, MAXCMDLENGTH); |
adehadd | 27:ce05fed3c1ea | 394 | |
adehadd | 27:ce05fed3c1ea | 395 | cmdIndx = 0; |
adehadd | 27:ce05fed3c1ea | 396 | |
adehadd | 27:ce05fed3c1ea | 397 | inCharQIdx = 0; |
adehadd | 27:ce05fed3c1ea | 398 | // inCharQIdx = MAXCMDLENGTH-1; |
iachinweze1 | 23:ab1cb51527d1 | 399 | |
iachinweze1 | 23:ab1cb51527d1 | 400 | |
iachinweze1 | 23:ab1cb51527d1 | 401 | |
adehadd | 27:ce05fed3c1ea | 402 | pc.attach(callback(this, &Comm::serialISR)); |
iachinweze1 | 23:ab1cb51527d1 | 403 | |
adehadd | 27:ce05fed3c1ea | 404 | // Thread t_comm_in(osPriorityAboveNormal, 1024); |
adehadd | 27:ce05fed3c1ea | 405 | // Thread t_comm_out(osPriorityAboveNormal, 1024); |
adehadd | 27:ce05fed3c1ea | 406 | // Thread t_motor_ctrl(osPriorityAboveNormal, 1024); |
iachinweze1 | 23:ab1cb51527d1 | 407 | |
adehadd | 27:ce05fed3c1ea | 408 | motorPower = 300; |
adehadd | 27:ce05fed3c1ea | 409 | targetVel = 45.0; |
adehadd | 27:ce05fed3c1ea | 410 | targetRot = 459.0; |
adehadd | 27:ce05fed3c1ea | 411 | |
adehadd | 27:ce05fed3c1ea | 412 | |
adehadd | 27:ce05fed3c1ea | 413 | |
adehadd | 27:ce05fed3c1ea | 414 | /*MsgChar = {'m', 'R', 'V', 'r', 'v', |
adehadd | 27:ce05fed3c1ea | 415 | |
adehadd | 27:ce05fed3c1ea | 416 | 'h', 'K', 'n', |
iachinweze1 | 23:ab1cb51527d1 | 417 | |
adehadd | 27:ce05fed3c1ea | 418 | 'T', 'r', |
adehadd | 27:ce05fed3c1ea | 419 | |
adehadd | 27:ce05fed3c1ea | 420 | 'e'};*/ |
adehadd | 27:ce05fed3c1ea | 421 | } |
adehadd | 27:ce05fed3c1ea | 422 | |
iachinweze1 | 23:ab1cb51527d1 | 423 | |
adehadd | 27:ce05fed3c1ea | 424 | void putMessage(msgType type, uint32_t message){ |
adehadd | 27:ce05fed3c1ea | 425 | msg *p_msg = mailStack.alloc(); |
adehadd | 27:ce05fed3c1ea | 426 | p_msg->type = type; |
adehadd | 27:ce05fed3c1ea | 427 | p_msg->message = message; |
adehadd | 27:ce05fed3c1ea | 428 | mailStack.put(p_msg); |
adehadd | 27:ce05fed3c1ea | 429 | } |
iachinweze1 | 23:ab1cb51527d1 | 430 | |
adehadd | 27:ce05fed3c1ea | 431 | void start_comm(){ |
adehadd | 27:ce05fed3c1ea | 432 | _RUN = true; |
iachinweze1 | 23:ab1cb51527d1 | 433 | |
adehadd | 20:c60f4785b556 | 434 | |
adehadd | 27:ce05fed3c1ea | 435 | // reset buffer |
adehadd | 27:ce05fed3c1ea | 436 | // MbedOS prints 'Embedded Systems are fun and do awesome things!' |
adehadd | 27:ce05fed3c1ea | 437 | // if you print a null terminator |
adehadd | 27:ce05fed3c1ea | 438 | pc.putc('>'); |
adehadd | 27:ce05fed3c1ea | 439 | for (int i = 0; i < MAXCMDLENGTH; ++i) { |
adehadd | 27:ce05fed3c1ea | 440 | inCharQ[i] = '.'; |
adehadd | 27:ce05fed3c1ea | 441 | pc.putc('.'); |
iachinweze1 | 23:ab1cb51527d1 | 442 | } |
adehadd | 27:ce05fed3c1ea | 443 | pc.putc('<'); |
adehadd | 27:ce05fed3c1ea | 444 | pc.putc('\r'); |
adehadd | 27:ce05fed3c1ea | 445 | |
adehadd | 27:ce05fed3c1ea | 446 | inCharQ[MAXCMDLENGTH] = '\0'; |
adehadd | 27:ce05fed3c1ea | 447 | strncpy(newCmd, inCharQ, MAXCMDLENGTH); |
adehadd | 27:ce05fed3c1ea | 448 | |
adehadd | 27:ce05fed3c1ea | 449 | // returnCursor(); |
adehadd | 20:c60f4785b556 | 450 | |
adehadd | 27:ce05fed3c1ea | 451 | // t_comm_in.start(callback(this, &Comm::commInFn)); |
adehadd | 27:ce05fed3c1ea | 452 | // this::thread::wait() |
adehadd | 27:ce05fed3c1ea | 453 | // wait(1.0); |
adehadd | 27:ce05fed3c1ea | 454 | t_comm_out.start(callback(this, &Comm::commOutFn)); |
adehadd | 27:ce05fed3c1ea | 455 | t_motor_ctrl.start(callback(this, &Comm::motorCtrlFn)); |
adehadd | 27:ce05fed3c1ea | 456 | |
adehadd | 27:ce05fed3c1ea | 457 | |
adehadd | 27:ce05fed3c1ea | 458 | } |
iachinweze1 | 23:ab1cb51527d1 | 459 | |
adehadd | 27:ce05fed3c1ea | 460 | char newCmd[]; // because unallocated must be defined at the bottom of the class |
adehadd | 27:ce05fed3c1ea | 461 | char inCharQ[]; |
adehadd | 27:ce05fed3c1ea | 462 | }; |
CallumAlder | 19:805c87360b55 | 463 | |
adehadd | 27:ce05fed3c1ea | 464 | |
adehadd | 20:c60f4785b556 | 465 | |
adehadd | 27:ce05fed3c1ea | 466 | //Set a given drive state |
adehadd | 27:ce05fed3c1ea | 467 | void motorOut(int8_t driveState){ |
iachinweze1 | 23:ab1cb51527d1 | 468 | |
adehadd | 20:c60f4785b556 | 469 | //Lookup the output byte from the drive state. |
adehadd | 20:c60f4785b556 | 470 | int8_t driveOut = driveTable[driveState & 0x07]; |
adehadd | 27:ce05fed3c1ea | 471 | |
adehadd | 20:c60f4785b556 | 472 | //Turn off first |
adehadd | 27:ce05fed3c1ea | 473 | if (~driveOut & 0x01) L1L = 0; |
adehadd | 20:c60f4785b556 | 474 | if (~driveOut & 0x02) L1H = 1; |
adehadd | 27:ce05fed3c1ea | 475 | if (~driveOut & 0x04) L2L = 0; |
adehadd | 20:c60f4785b556 | 476 | if (~driveOut & 0x08) L2H = 1; |
adehadd | 27:ce05fed3c1ea | 477 | if (~driveOut & 0x10) L3L = 0; |
adehadd | 20:c60f4785b556 | 478 | if (~driveOut & 0x20) L3H = 1; |
adehadd | 27:ce05fed3c1ea | 479 | |
adehadd | 20:c60f4785b556 | 480 | //Then turn on |
adehadd | 27:ce05fed3c1ea | 481 | if (driveOut & 0x01) L1L = 1; |
adehadd | 20:c60f4785b556 | 482 | if (driveOut & 0x02) L1H = 0; |
adehadd | 27:ce05fed3c1ea | 483 | if (driveOut & 0x04) L2L = 1; |
adehadd | 20:c60f4785b556 | 484 | if (driveOut & 0x08) L2H = 0; |
adehadd | 27:ce05fed3c1ea | 485 | if (driveOut & 0x10) L3L = 1; |
adehadd | 20:c60f4785b556 | 486 | if (driveOut & 0x20) L3H = 0; |
iachinweze1 | 23:ab1cb51527d1 | 487 | } |
iachinweze1 | 23:ab1cb51527d1 | 488 | |
adehadd | 27:ce05fed3c1ea | 489 | //Convert photointerrupter inputs to a rotor state |
adehadd | 20:c60f4785b556 | 490 | inline int8_t readRotorState(){ |
adehadd | 20:c60f4785b556 | 491 | return stateMap[I1 + 2*I2 + 4*I3]; |
iachinweze1 | 23:ab1cb51527d1 | 492 | } |
adehadd | 20:c60f4785b556 | 493 | |
adehadd | 27:ce05fed3c1ea | 494 | //Basic synchronisation routine |
adehadd | 20:c60f4785b556 | 495 | int8_t motorHome() { |
adehadd | 20:c60f4785b556 | 496 | //Put the motor in drive state 0 and wait for it to stabilise |
adehadd | 27:ce05fed3c1ea | 497 | motorOut(0); |
adehadd | 20:c60f4785b556 | 498 | wait(2.0); |
adehadd | 27:ce05fed3c1ea | 499 | |
adehadd | 20:c60f4785b556 | 500 | //Get the rotor state |
adehadd | 20:c60f4785b556 | 501 | return readRotorState(); |
adehadd | 20:c60f4785b556 | 502 | } |
adehadd | 20:c60f4785b556 | 503 | |
adehadd | 20:c60f4785b556 | 504 | |
adehadd | 27:ce05fed3c1ea | 505 | void stateUpdate(int8_t *params[]) { // () { // **params |
adehadd | 27:ce05fed3c1ea | 506 | *params[0] = readRotorState(); |
adehadd | 27:ce05fed3c1ea | 507 | int8_t currentState = *params[0]; |
adehadd | 27:ce05fed3c1ea | 508 | int8_t offset = *params[1]; |
adehadd | 27:ce05fed3c1ea | 509 | |
adehadd | 27:ce05fed3c1ea | 510 | switch (currentState) { |
adehadd | 27:ce05fed3c1ea | 511 | case 1: |
adehadd | 27:ce05fed3c1ea | 512 | stateCount[0]++; |
adehadd | 27:ce05fed3c1ea | 513 | break; |
adehadd | 27:ce05fed3c1ea | 514 | case (1 + lead): |
adehadd | 27:ce05fed3c1ea | 515 | stateCount[1]++; |
adehadd | 27:ce05fed3c1ea | 516 | break; |
adehadd | 27:ce05fed3c1ea | 517 | case (1 + (lead*2)): |
adehadd | 27:ce05fed3c1ea | 518 | stateCount[2]++; |
adehadd | 27:ce05fed3c1ea | 519 | break; |
adehadd | 27:ce05fed3c1ea | 520 | } |
adehadd | 27:ce05fed3c1ea | 521 | |
adehadd | 27:ce05fed3c1ea | 522 | motorOut((currentState - offset + lead + 6) % 6); |
adehadd | 26:fb6151e5907d | 523 | } |
adehadd | 26:fb6151e5907d | 524 | |
adehadd | 27:ce05fed3c1ea | 525 | //Main |
adehadd | 27:ce05fed3c1ea | 526 | int main() { |
adehadd | 26:fb6151e5907d | 527 | |
adehadd | 27:ce05fed3c1ea | 528 | // std::ios::sync_with_stdio(false); |
adehadd | 27:ce05fed3c1ea | 529 | Comm comm_plz; |
adehadd | 27:ce05fed3c1ea | 530 | |
adehadd | 27:ce05fed3c1ea | 531 | // comm_plz.pc.printf("%s\n", "do i work bruh" ); // using printf of class is calm |
adehadd | 27:ce05fed3c1ea | 532 | SHA256 Miner; |
adehadd | 27:ce05fed3c1ea | 533 | |
adehadd | 27:ce05fed3c1ea | 534 | uint8_t sequence[] = {0x45,0x6D,0x62,0x65,0x64,0x64,0x65,0x64, |
adehadd | 27:ce05fed3c1ea | 535 | 0x20,0x53,0x79,0x73,0x74,0x65,0x6D,0x73, |
adehadd | 27:ce05fed3c1ea | 536 | 0x20,0x61,0x72,0x65,0x20,0x66,0x75,0x6E, |
adehadd | 27:ce05fed3c1ea | 537 | 0x20,0x61,0x6E,0x64,0x20,0x64,0x6F,0x20, |
adehadd | 27:ce05fed3c1ea | 538 | 0x61,0x77,0x65,0x73,0x6F,0x6D,0x65,0x20, |
adehadd | 27:ce05fed3c1ea | 539 | 0x74,0x68,0x69,0x6E,0x67,0x73,0x21,0x20, |
adehadd | 27:ce05fed3c1ea | 540 | 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, |
adehadd | 27:ce05fed3c1ea | 541 | 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}; |
adehadd | 27:ce05fed3c1ea | 542 | uint64_t* key = (uint64_t*)((int)sequence + 48); |
adehadd | 27:ce05fed3c1ea | 543 | uint64_t* nonce = (uint64_t*)((int)sequence + 56); |
adehadd | 27:ce05fed3c1ea | 544 | uint8_t hash[32]; |
adehadd | 27:ce05fed3c1ea | 545 | uint32_t length64 = 64; |
adehadd | 27:ce05fed3c1ea | 546 | uint32_t hashCounter = 0; |
adehadd | 27:ce05fed3c1ea | 547 | Timer timer; |
adehadd | 27:ce05fed3c1ea | 548 | |
adehadd | 27:ce05fed3c1ea | 549 | float dutyC = 1; // 100% |
adehadd | 27:ce05fed3c1ea | 550 | float mtrPeriod = 2e-3; // motor period |
adehadd | 27:ce05fed3c1ea | 551 | |
adehadd | 27:ce05fed3c1ea | 552 | pwmCtrl.period(mtrPeriod); |
adehadd | 27:ce05fed3c1ea | 553 | pwmCtrl.pulsewidth(mtrPeriod*dutyC); |
adehadd | 27:ce05fed3c1ea | 554 | |
adehadd | 27:ce05fed3c1ea | 555 | comm_plz.start_comm(); |
iachinweze1 | 23:ab1cb51527d1 | 556 | |
adehadd | 27:ce05fed3c1ea | 557 | // Motor States |
adehadd | 27:ce05fed3c1ea | 558 | int8_t orState = 0; //Rotot offset at motor state 0 |
adehadd | 27:ce05fed3c1ea | 559 | int8_t currentState = 0; //Rotot offset at motor state 0 |
adehadd | 27:ce05fed3c1ea | 560 | int8_t stateList[6]; //Rotot offset at motor state 0 |
adehadd | 27:ce05fed3c1ea | 561 | //Run the motor synchronisation |
adehadd | 27:ce05fed3c1ea | 562 | orState = motorHome(); |
adehadd | 27:ce05fed3c1ea | 563 | |
adehadd | 27:ce05fed3c1ea | 564 | theStates[0] = orState; |
adehadd | 27:ce05fed3c1ea | 565 | theStates[1] = (orState + lead) % 6; |
adehadd | 27:ce05fed3c1ea | 566 | theStates[2] = (orState + (lead*2)) % 6; |
adehadd | 27:ce05fed3c1ea | 567 | |
adehadd | 27:ce05fed3c1ea | 568 | // Add callbacks |
adehadd | 27:ce05fed3c1ea | 569 | // I1.fall(&stateUpdate); |
adehadd | 27:ce05fed3c1ea | 570 | // I2.fall(&stateUpdate); |
adehadd | 27:ce05fed3c1ea | 571 | // I3.fall(&stateUpdate); |
adehadd | 27:ce05fed3c1ea | 572 | int8_t* params[2]; |
adehadd | 27:ce05fed3c1ea | 573 | params[0] = ¤tState; |
adehadd | 27:ce05fed3c1ea | 574 | params[1] = &orState; |
iachinweze1 | 24:be5fef3dace1 | 575 | |
adehadd | 27:ce05fed3c1ea | 576 | I1.fall(callback(&stateUpdate,params)); |
adehadd | 27:ce05fed3c1ea | 577 | I2.fall(callback(&stateUpdate,params)); |
adehadd | 27:ce05fed3c1ea | 578 | I3.fall(callback(&stateUpdate,params)); |
adehadd | 26:fb6151e5907d | 579 | |
adehadd | 27:ce05fed3c1ea | 580 | I1.rise(callback(&stateUpdate,params)); |
adehadd | 27:ce05fed3c1ea | 581 | I2.rise(callback(&stateUpdate,params)); |
adehadd | 27:ce05fed3c1ea | 582 | I3.rise(callback(&stateUpdate,params)); |
adehadd | 26:fb6151e5907d | 583 | |
adehadd | 27:ce05fed3c1ea | 584 | // Push motor to move |
adehadd | 27:ce05fed3c1ea | 585 | currentState = readRotorState(); |
adehadd | 27:ce05fed3c1ea | 586 | motorOut((currentState-orState+lead+6)%6); // We push it digitally |
adehadd | 26:fb6151e5907d | 587 | |
adehadd | 27:ce05fed3c1ea | 588 | // pc.printf("Rotor origin: %x\n\r",orState); |
adehadd | 27:ce05fed3c1ea | 589 | // orState is subtracted from future rotor state inputs to align rotor and motor states |
adehadd | 27:ce05fed3c1ea | 590 | // intState = readRotorState(); |
adehadd | 27:ce05fed3c1ea | 591 | //if (intState != intStateOld) { |
adehadd | 27:ce05fed3c1ea | 592 | // pc.printf("old:%d \t new:%d \t next:%d \n\r",intStateOld, intState, (intState-orState+lead+6)%6); |
adehadd | 27:ce05fed3c1ea | 593 | // intStateOld = intState; |
adehadd | 27:ce05fed3c1ea | 594 | // motorOut((intState-orState+lead+6)%6); //+6 to make sure the remainder is positive |
adehadd | 27:ce05fed3c1ea | 595 | // } |
adehadd | 20:c60f4785b556 | 596 | |
adehadd | 27:ce05fed3c1ea | 597 | dutyC = 0.8; |
adehadd | 27:ce05fed3c1ea | 598 | pwmCtrl.pulsewidth(mtrPeriod*dutyC); |
CallumAlder | 19:805c87360b55 | 599 | |
adehadd | 20:c60f4785b556 | 600 | |
adehadd | 27:ce05fed3c1ea | 601 | // Keep the program running indefinitely |
adehadd | 27:ce05fed3c1ea | 602 | timer.start(); // start timer |
adehadd | 27:ce05fed3c1ea | 603 | int stateCount = 0; |
adehadd | 27:ce05fed3c1ea | 604 | while (1) { |
adehadd | 27:ce05fed3c1ea | 605 | // pc.printf("Current:%d \t Next:%d \n\r", currentState, (currentState-orState+lead+6)%6); |
adehadd | 27:ce05fed3c1ea | 606 | comm_plz.newKey_mutex.lock(); |
adehadd | 27:ce05fed3c1ea | 607 | *key = comm_plz.newKey; |
adehadd | 27:ce05fed3c1ea | 608 | comm_plz.newKey_mutex.unlock(); |
adehadd | 27:ce05fed3c1ea | 609 | Miner.computeHash(hash, sequence, length64); |
adehadd | 27:ce05fed3c1ea | 610 | hashCounter++; |
adehadd | 27:ce05fed3c1ea | 611 | if ((hash[0]==0) && (hash[1]==0)){ |
adehadd | 27:ce05fed3c1ea | 612 | comm_plz.putMessage((Comm::msgType)7, *nonce); |
adehadd | 26:fb6151e5907d | 613 | } |
adehadd | 26:fb6151e5907d | 614 | |
adehadd | 27:ce05fed3c1ea | 615 | // Try a new nonce |
adehadd | 27:ce05fed3c1ea | 616 | (*nonce)++; |
adehadd | 26:fb6151e5907d | 617 | |
adehadd | 27:ce05fed3c1ea | 618 | if (stateCount<6){ |
adehadd | 27:ce05fed3c1ea | 619 | stateList[stateCount] = currentState; |
adehadd | 27:ce05fed3c1ea | 620 | stateCount++; |
adehadd | 26:fb6151e5907d | 621 | } |
adehadd | 26:fb6151e5907d | 622 | else { |
adehadd | 27:ce05fed3c1ea | 623 | //pc.printf("states"); |
adehadd | 27:ce05fed3c1ea | 624 | //for(int i = 0; i < 6; ++i) |
adehadd | 27:ce05fed3c1ea | 625 | //pc.printf("%02i,", stateList[i]); |
adehadd | 27:ce05fed3c1ea | 626 | //pc.printf("\n\r"); |
adehadd | 27:ce05fed3c1ea | 627 | stateCount = 0; |
CallumAlder | 15:2f95f2fb68e3 | 628 | } |
CallumAlder | 15:2f95f2fb68e3 | 629 | |
adehadd | 27:ce05fed3c1ea | 630 | // Per Second i.e. when greater or equal to 1 |
adehadd | 27:ce05fed3c1ea | 631 | if (timer.read() >= 1){ |
adehadd | 27:ce05fed3c1ea | 632 | comm_plz.putMessage((Comm::msgType)5, hashCounter); |
adehadd | 27:ce05fed3c1ea | 633 | //pc.printf("HashRate = %02u \n\r",hashCounter); |
adehadd | 27:ce05fed3c1ea | 634 | hashCounter=0; |
adehadd | 27:ce05fed3c1ea | 635 | timer.reset(); |
adehadd | 18:7ee632098fd4 | 636 | } |
CallumAlder | 15:2f95f2fb68e3 | 637 | } |
adehadd | 27:ce05fed3c1ea | 638 | } |