Omar Muttawa
/
SMARTASSES_FINAL_CW2
SMARTASSES 2019
Embed:
(wiki syntax)
Show/hide line numbers
main.cpp
00001 //SMARTASSES 00002 00003 #include "mbed.h" 00004 #include "SHA256.h" 00005 #include <string> 00006 #include <vector> 00007 #include <RawSerial.h> 00008 00009 //Photointerrupter input pins 00010 #define I1pin D3 00011 #define I2pin D6 00012 #define I3pin D5 00013 00014 //Incremental encoder input pins 00015 #define CHApin D12 00016 #define CHBpin D11 00017 00018 //Motor Drive output pins //Mask in output byte 00019 #define L1Lpin D1 //0x01 00020 #define L1Hpin A3 //0x02 00021 #define L2Lpin D0 //0x04 00022 #define L2Hpin A6 //0x08 00023 #define L3Lpin D10 //0x10 00024 #define L3Hpin D2 //0x20 00025 00026 #define PWMpin D9 00027 00028 //Motor current sense 00029 #define MCSPpin A1 00030 #define MCSNpin A0 00031 00032 #define TESTPIN D4 //USED FOR TIMING ETC 00033 00034 //Mapping from sequential drive states to motor phase outputs 00035 /* 00036 State L1 L2 L3 00037 0 H - L 00038 1 - H L 00039 2 L H - 00040 3 L - H 00041 4 - L H 00042 5 H L - 00043 6 - - - 00044 7 - - - 00045 */ 00046 //Drive state to output table 00047 const int8_t driveTable[] = {0x12,0x18,0x09,0x21,0x24,0x06,0x00,0x00}; 00048 00049 //Mapping from interrupter inputs to sequential rotor states. 0x00 and 0x07 are not valid 00050 const int8_t stateMap[] = {0x07,0x05,0x03,0x04,0x01,0x00,0x02,0x07}; 00051 //const int8_t stateMap[] = {0x07,0x01,0x03,0x02,0x05,0x00,0x04,0x07}; //Alternative if phase order of input or drive is reversed 00052 00053 //Phase lead to make motor spin 00054 volatile int8_t lead = 2; //2 for forwards, -2 for backwards 00055 00056 //Status LED 00057 DigitalOut led1(LED1); 00058 DigitalOut testPin(TESTPIN); 00059 00060 //Photointerrupter inputs 00061 InterruptIn I1(I1pin); 00062 InterruptIn I2(I2pin); 00063 InterruptIn I3(I3pin); 00064 00065 //Global varibale to count revolutions up to 6 00066 volatile int count_revolution = 0; 00067 volatile int number_of_notes = 0; 00068 volatile int last_count_revolution = 0; 00069 //TUNING PARAMETERS FOR SPEED CONTROLLER 00070 volatile float K_PS = 0.1; 00071 volatile float K_IS = 0.18; 00072 volatile float K_DS = 0.0001; 00073 volatile float VELOCITY_INTEGRAL_LIMIT = 100; 00074 //TUNING PARAMETERS FOR REVOLUTION CONTROLLER 00075 volatile float K_PR= 0.1; 00076 volatile float K_IR = 0.001; 00077 volatile float K_DR = 0.05; 00078 volatile float ROTATION_INTEGRAL_LIMIT = 100; 00079 00080 float timeSinceLastRun; 00081 float elapsedTime = 0; 00082 00083 string tune; 00084 char tune_c_str[50]; 00085 00086 char notes [50]; //hold the notes 00087 float periods[50]; 00088 int durations[50]; //holds the durations 00089 volatile bool playTune = false; 00090 bool playTuneLocal = false; //used to prevent deadlocks and long mutexs 00091 int noteIndex = 0; 00092 00093 //PWM Class: 00094 PwmOut PWM_pin(PWMpin); 00095 00096 //Motor Drive outputs 00097 DigitalOut L1L(L1Lpin); 00098 DigitalOut L1H(L1Hpin); 00099 DigitalOut L2L(L2Lpin); 00100 DigitalOut L2H(L2Hpin); 00101 DigitalOut L3L(L3Lpin); 00102 DigitalOut L3H(L3Hpin); 00103 00104 /* Mail */ 00105 typedef struct { 00106 int type; //0 means it will be a string, 1 means it will be uint64 00107 uint64_t uint64_message; 00108 char* string_message; 00109 float float_message; 00110 } mail_t; 00111 00112 //Declaration of timer global variable 00113 Timer t; 00114 00115 //Declaration of timer for velocity calculations global variable 00116 Timer motorCtrlTimer; 00117 00118 //Threads' declaration 00119 Thread printMsgT; 00120 Thread readMsgT; 00121 Thread motorCtrlT(osPriorityHigh,1024); 00122 00123 //Declaration of Mail global object 00124 Mail<mail_t, 16> mail_box; 00125 00126 //Global to keep to previous position necessary for velocity calculations 00127 float prevPosition; 00128 00129 //Global for motor's position 00130 float motor_position = 0; 00131 float current_position = 0; 00132 00133 //Global variables 00134 int8_t intState,intStateOld,orState; 00135 00136 RawSerial pc(SERIAL_TX, SERIAL_RX); 00137 Queue<void, 8> inCharQ; 00138 uint64_t newKey; 00139 float Ts,Tr,newTorque; 00140 volatile float rot_input=0; 00141 volatile float max_vel = 10; 00142 volatile int exec_count = 0; 00143 00144 Mutex newKey_mutex; 00145 Mutex newRotation_mutex; 00146 Mutex newVelocity_mutex; 00147 Mutex countRev_mutex; 00148 Mutex playTune_mutex; 00149 int hashRate; 00150 00151 volatile float velocityError = 0; 00152 volatile float prevVelocityError=0; 00153 volatile float differentialVelocityError = 0; 00154 volatile float integralVelocityError = 0; 00155 00156 volatile float rotationError = 0; 00157 volatile float prevRotationError = 0; 00158 volatile float differentialRotationError = 0; 00159 volatile float integralRotationError = 0; 00160 00161 float max_t = 0; 00162 00163 int target_position,position_error; 00164 00165 //Global variable for velocity 00166 volatile float velocity; 00167 00168 //Set a given drive state 00169 void motorOut(int8_t driveState){ 00170 00171 //Lookup the output byte from the drive state. 00172 int8_t driveOut = driveTable[driveState & 0x07]; 00173 00174 //Turn off first 00175 if (~driveOut & 0x01) L1L = 0; 00176 if (~driveOut & 0x02) L1H = 1; 00177 if (~driveOut & 0x04) L2L = 0; 00178 if (~driveOut & 0x08) L2H = 1; 00179 if (~driveOut & 0x10) L3L = 0; 00180 if (~driveOut & 0x20) L3H = 1; 00181 00182 //Then turn on 00183 if (driveOut & 0x01) L1L = 1; 00184 if (driveOut & 0x02) L1H = 0; 00185 if (driveOut & 0x04) L2L = 1; 00186 if (driveOut & 0x08) L2H = 0; 00187 if (driveOut & 0x10) L3L = 1; 00188 if (driveOut & 0x20) L3H = 0; 00189 } 00190 00191 //Convert photointerrupter inputs to a rotor state 00192 inline int8_t readRotorState(){ 00193 return stateMap[I1 + 2*I2 + 4*I3]; 00194 } 00195 00196 void Rotorcalib(){ 00197 intState = readRotorState(); 00198 if (intState != intStateOld) { 00199 //lead_mutex.lock(); 00200 motorOut((intState-orState+lead+6)%6); //+6 to make sure the remainder is positive 00201 //lead_mutex.unlock(); 00202 //pc.printf("%d\n\r",intState); 00203 if (intState-intStateOld==-5){ 00204 //Goes positive direction 00205 motor_position++; 00206 }else if (intState-intStateOld==5) { 00207 //Goes negative direction 00208 motor_position--; 00209 }else{ 00210 motor_position = motor_position + (intState-intStateOld); //every 00211 } 00212 //Update state 00213 intStateOld = intState; 00214 } 00215 } 00216 00217 //Basic synchronisation routine 00218 int8_t motorHome() { 00219 00220 //Put the motor in drive state 0 and wait for it to stabilise 00221 motorOut(0); 00222 wait(2.0); 00223 motorOut(1.0); 00224 00225 //Get the rotor state 00226 return readRotorState(); 00227 } 00228 00229 //Print message from Mail_box 00230 void printMsgFn (void) { 00231 while(1){ 00232 00233 //Recieve a message and print it 00234 osEvent evt = mail_box.get(); 00235 00236 if (evt.status == osEventMail) { 00237 mail_t *mail = (mail_t*)evt.value.p; 00238 if(mail->type == 1){ //int 00239 printf("%llu\n\r", mail->uint64_message); 00240 } 00241 else if(mail->type == 2){ 00242 //string! 00243 printf("%s", mail->string_message); 00244 }else if (mail->type==3){ 00245 printf("%f\n\r", mail->float_message); 00246 } 00247 mail_box.free(mail); 00248 } 00249 } 00250 } 00251 00252 //Create a int tupe Mail_box object 00253 void put_msg_int (uint64_t uint64_message) { 00254 mail_t *mail = mail_box.alloc(); 00255 mail->type=1; 00256 mail->uint64_message = uint64_message; 00257 mail_box.put(mail); 00258 } 00259 00260 //Create a string tupe Mail_box object 00261 void put_msg_string (char* message) { 00262 mail_t *mail = mail_box.alloc(); 00263 mail->type=2; 00264 mail->string_message = message; 00265 mail_box.put(mail); 00266 } 00267 00268 void put_msg_float (float message) { 00269 mail_t *mail = mail_box.alloc(); 00270 mail->type=3; 00271 mail->float_message = message; 00272 mail_box.put(mail); 00273 } 00274 00275 //Serial read 00276 void serialISR(){ 00277 //testPin.write(1); 00278 uint8_t newChar = pc.getc(); 00279 inCharQ.put((void*)newChar); 00280 //testPin.write(0); 00281 } 00282 00283 //The function the ticker calls 00284 void motorCtrlTick(){ 00285 motorCtrlT.signal_set(0x1); 00286 } 00287 00288 void printNotes(void){ 00289 put_msg_string(notes); 00290 for(int i = 0; i < number_of_notes; i++){ 00291 put_msg_float((float)durations[i]); 00292 } 00293 for(int i = 0; i < number_of_notes; i++){ 00294 put_msg_float((float)periods[i]); 00295 } 00296 } 00297 00298 void processTuneString(void){ 00299 playTune_mutex.lock(); 00300 playTune = false; 00301 playTune_mutex.unlock(); 00302 strcpy(tune_c_str, tune.c_str()); //turn tune (string) into c style string 00303 number_of_notes = 0; 00304 //reset the arrays 00305 for(int i =0; i<10; i++){ 00306 notes[i] = '\0'; 00307 durations[i] = -1; 00308 } 00309 00310 char current_char; 00311 char prev_char; 00312 int tune_string_length = strlen(tune_c_str); 00313 int a; 00314 noteIndex = 0; 00315 00316 for(a = 0; a < tune_string_length; a++){ 00317 current_char = tune_c_str[a]; 00318 if((current_char >= 'A') &&(current_char <= 'G')){ 00319 notes[number_of_notes] = current_char; 00320 number_of_notes++; 00321 } 00322 else if((current_char >= '1') && (current_char <= '9')) 00323 durations[number_of_notes - 1] = (int)current_char - 48; 00324 00325 else if(current_char == '#'){ 00326 prev_char = tune_c_str[a-1]; 00327 switch(prev_char){ 00328 case 'A': 00329 notes[number_of_notes - 1] = 'b'; 00330 break; 00331 case 'C': 00332 notes[number_of_notes - 1] = 'd'; 00333 break; 00334 case 'D': 00335 notes[number_of_notes - 1] = 'e'; 00336 break; 00337 case 'F': 00338 notes[number_of_notes - 1] = 'g'; 00339 break; 00340 case 'G': 00341 notes[number_of_notes - 1] = 'a'; 00342 break; 00343 } 00344 } //end of # 00345 else if(current_char == '^'){ 00346 prev_char = tune_c_str[a-1]; 00347 switch(prev_char){ 00348 case 'B': 00349 notes[number_of_notes - 1] = 'b'; 00350 break; 00351 case 'D': 00352 notes[number_of_notes - 1] = 'd'; 00353 break; 00354 case 'E': 00355 notes[number_of_notes - 1] = 'e'; 00356 break; 00357 case 'G': 00358 notes[number_of_notes - 1] = 'g'; 00359 break; 00360 case 'A': 00361 notes[number_of_notes - 1] = 'a'; 00362 break; 00363 }//end of switch 00364 } //end of ^ 00365 00366 }//end of the for loop 00367 for(a = 0; a < number_of_notes; a++){ 00368 char current_note = notes[a]; 00369 switch(current_note){ 00370 case 'A': periods[a] = 1.0/440.0; 00371 break; 00372 case 'b': periods[a] = 1.0/0466.16; 00373 break; 00374 case 'B': periods[a] = 1.0/493.88; 00375 break; 00376 case 'C': periods[a] = 1.0/523.25; 00377 break; 00378 case 'd': periods[a] = 1.0/554.37; 00379 break; 00380 case 'D': periods[a] = 1.0/587.83; 00381 break; 00382 case 'e': periods[a] = 1.0/622.25; 00383 break; 00384 case 'E': periods[a] = 1.0/659.25; 00385 break; 00386 case 'F': periods[a] = 1.0/698.46; 00387 break; 00388 case 'g': periods[a] = 1.0/739.99; 00389 break; 00390 case 'G': periods[a] = 1.0/783.99; 00391 break; 00392 case 'a': periods[a] = 1.0/830.61; 00393 break; 00394 default: periods[a] = 1.0/440.0; 00395 break; 00396 }//end of switch 00397 }//end of for 00398 playTune_mutex.lock(); 00399 playTune = true; 00400 playTune_mutex.unlock(); 00401 return; 00402 } 00403 00404 00405 //Run in the motorCtrl thread 00406 void motorCtrlFn(){ 00407 char msg[50]; 00408 Ticker motorCtrlTicker; 00409 motorCtrlTicker.attach_us(&motorCtrlTick,100000); //run every 100ms 00410 prevPosition=motor_position; 00411 //Start velocity times 00412 motorCtrlTimer.start(); 00413 while(1){ 00414 //Wait for ticker message 00415 00416 motorCtrlT.signal_wait(0x1); 00417 testPin.write(1); 00418 motorCtrlTimer.stop(); 00419 timeSinceLastRun = motorCtrlTimer.read(); 00420 motorCtrlTimer.reset(); 00421 motorCtrlTimer.start(); 00422 //play tune 00423 00424 playTune_mutex.lock(); 00425 playTuneLocal = playTune; 00426 playTune_mutex.unlock(); 00427 00428 if(playTuneLocal == true){ 00429 elapsedTime = elapsedTime + timeSinceLastRun; //increment the 00430 float currentDuration = durations[noteIndex]; 00431 if(elapsedTime >= currentDuration){ 00432 elapsedTime = 0; 00433 noteIndex++; 00434 if(noteIndex == number_of_notes) 00435 noteIndex = 0; //reset if needed 00436 PWM_pin.period(periods[noteIndex]); //set the 00437 } 00438 } 00439 else //if playTune == false 00440 PWM_pin.period(0.002f); 00441 00442 00443 //Calculate velocity 00444 core_util_critical_section_enter(); 00445 current_position=motor_position; 00446 core_util_critical_section_exit(); 00447 00448 velocity = (float)((current_position - prevPosition)/(6.0*timeSinceLastRun)); //rps 00449 prevPosition=current_position; 00450 00451 if((max_vel == 0) && (target_position == 0)){ //no limits 00452 lead = 2; 00453 PWM_pin.write(1.0); 00454 } 00455 00456 //speed limit no rotation limit, run forever at defined speed 00457 else if ((max_vel != 0) && (target_position == 0)){ 00458 prevVelocityError = velocityError; 00459 00460 velocityError = max_vel - abs(velocity); //Proportional 00461 differentialVelocityError = (velocityError - prevVelocityError)/timeSinceLastRun; //Differential 00462 integralVelocityError += velocityError*timeSinceLastRun; // Integral 00463 00464 if(integralVelocityError > VELOCITY_INTEGRAL_LIMIT) //Limit the integral 00465 integralVelocityError = VELOCITY_INTEGRAL_LIMIT; 00466 if(integralVelocityError < -1*VELOCITY_INTEGRAL_LIMIT) 00467 integralVelocityError =(-1*VELOCITY_INTEGRAL_LIMIT); 00468 00469 Ts = K_PS*velocityError + K_IS*integralVelocityError + K_DS*differentialVelocityError; 00470 00471 lead = (Ts<0) ? -2 : 2; 00472 00473 Ts = abs(Ts); 00474 if (Ts>1){ 00475 Ts=1.0; 00476 } 00477 PWM_pin.write(Ts); 00478 00479 } 00480 //no speed limit, but a rotation limit 00481 else if((max_vel == 0) && (target_position != 0)){ 00482 prevRotationError = rotationError; 00483 rotationError = target_position - current_position; //in ISR TICKS 00484 differentialRotationError = (rotationError - prevRotationError)/timeSinceLastRun; //in ISR ticks /s 00485 00486 00487 integralRotationError += rotationError*timeSinceLastRun; 00488 if(integralRotationError > ROTATION_INTEGRAL_LIMIT) 00489 integralRotationError = ROTATION_INTEGRAL_LIMIT; 00490 if(integralRotationError < -1*ROTATION_INTEGRAL_LIMIT) 00491 integralRotationError = -1*ROTATION_INTEGRAL_LIMIT; 00492 //put_msg_float(integralRotationError); 00493 Tr = (K_PR*rotationError) + (K_IR*integralRotationError) + (K_DR*differentialRotationError); // Need to divide by time 00494 00495 // In case the rotations were overshot change the direction back 00496 00497 lead = (Tr > 0) ? 2 : -2; //change direction if needed 00498 Tr = abs(Tr); 00499 Tr = (Tr > 1) ? 1 : Tr; //clamp at 1.0 00500 00501 if(abs(rotationError) == 0){ 00502 PWM_pin.write(0.0); 00503 } 00504 else 00505 PWM_pin.write(Tr); 00506 } 00507 //speed limit and rotation limit 00508 else{ //((max_vel != 0) && (target_position != 0)){{ 00509 prevRotationError = rotationError; 00510 rotationError = target_position - current_position; //in ISR TICKS 00511 float differentialRotationError = (rotationError - prevRotationError)/timeSinceLastRun; 00512 integralRotationError += (rotationError*timeSinceLastRun); 00513 if(integralRotationError > ROTATION_INTEGRAL_LIMIT) 00514 integralRotationError = ROTATION_INTEGRAL_LIMIT; 00515 if(integralRotationError < -1*ROTATION_INTEGRAL_LIMIT) 00516 integralRotationError = -1*ROTATION_INTEGRAL_LIMIT; 00517 //put_msg_float(integralRotationError); 00518 Tr = (K_PR*rotationError) + (K_IR*integralRotationError) + (K_DR*differentialRotationError); // Need to divide by time 00519 00520 prevVelocityError = velocityError; 00521 velocityError = max_vel - abs(velocity); 00522 float differentialVelocityError = (velocityError - prevVelocityError)/timeSinceLastRun; 00523 00524 // Integral error 00525 integralVelocityError += velocityError*timeSinceLastRun; 00526 if(integralVelocityError > VELOCITY_INTEGRAL_LIMIT) 00527 integralVelocityError = VELOCITY_INTEGRAL_LIMIT; 00528 if(integralVelocityError < -1*VELOCITY_INTEGRAL_LIMIT) 00529 integralVelocityError =(-1*VELOCITY_INTEGRAL_LIMIT); 00530 00531 Ts = K_PS*velocityError + K_IS*integralVelocityError + K_DS*differentialVelocityError; 00532 if(differentialRotationError < 0) 00533 Ts = -Ts; 00534 00535 00536 if(abs(velocity) > max_vel){ 00537 newTorque = min(abs(Tr), abs(Ts)); 00538 } 00539 else 00540 newTorque = max(abs(Tr), abs(Ts)); 00541 00542 if(abs(rotationError)<10) //if we're close, take Tr 00543 newTorque = abs(Tr); 00544 00545 lead = (rotationError >= 0) ? 2 : -2; 00546 00547 00548 00549 newTorque = abs(newTorque); 00550 00551 if(newTorque > 1.0) 00552 newTorque = 1.0; 00553 00554 if(abs(rotationError) == 0) 00555 PWM_pin.write(0.0); 00556 else 00557 PWM_pin.write(newTorque); 00558 00559 } 00560 testPin.write(0); 00561 }//end of while 1 00562 }//end of fn 00563 00564 00565 //Receiving command serially and decoding it 00566 void readMsgFn(){ 00567 string message_string; 00568 pc.attach(&serialISR); 00569 char message[18]; 00570 int i=0; 00571 while(1){ 00572 osEvent newEvent = inCharQ.get(); 00573 //testPin.write(1); 00574 uint8_t newChar = (uint8_t)newEvent.value.p; 00575 if(i >= 17) 00576 i=0; 00577 else{ 00578 message[i]=newChar; 00579 i++; 00580 } 00581 if(newChar=='\r' || newChar == '\n'){ 00582 if(message[0]=='K'){ 00583 newKey_mutex.lock(); 00584 put_msg_string("Entering New Key: "); 00585 sscanf(message,"K%x",&newKey); 00586 message[i]='\0'; 00587 put_msg_int(newKey); 00588 newKey_mutex.unlock(); 00589 i=0; 00590 } 00591 else if(message[0]=='R'){ 00592 newRotation_mutex.lock(); 00593 integralRotationError = 0; //reset the sum! 00594 integralVelocityError = 0; //reset the sum! 00595 sscanf(message,"R%f",&rot_input); //rot_input in number of revs 00596 if(rot_input == 0) 00597 target_position = 0; 00598 else 00599 { 00600 target_position = current_position + (rot_input*6); //in ISR TICKS 00601 } 00602 message[i]='\0'; 00603 newRotation_mutex.unlock(); 00604 i=0; 00605 } 00606 else if(message[0]=='V'){ 00607 newVelocity_mutex.lock(); 00608 sscanf(message,"V%f",&max_vel); 00609 integralVelocityError = 0; //reset the sum! 00610 integralRotationError = 0; //reset the sum! 00611 newVelocity_mutex.unlock(); 00612 //printf("%f",max_vel); 00613 message[i]='\0'; 00614 i=0; 00615 } 00616 else if(message[0] == 'T'){ 00617 sscanf(message,"T%s",tune); 00618 if(message[1] == '0'){ 00619 playTune_mutex.lock(); 00620 playTune = false; 00621 playTune_mutex.unlock(); 00622 } 00623 else 00624 processTuneString(); 00625 message[i] = '\0'; 00626 i=0; 00627 } 00628 } 00629 //testPin.write(0); 00630 } 00631 } 00632 00633 00634 //Main 00635 int main() { 00636 string msg="Hello World"; 00637 SHA256 mySHA256 = SHA256(); 00638 //put_msg("HELLO"); 00639 uint8_t sequence[] = {0x45,0x6D,0x62,0x65,0x64,0x64,0x65,0x64, 00640 0x20,0x53,0x79,0x73,0x74,0x65,0x6D,0x73, 00641 0x20,0x61,0x72,0x65,0x20,0x66,0x75,0x6E, 00642 0x20,0x61,0x6E,0x64,0x20,0x64,0x6F,0x20, 00643 0x61,0x77,0x65,0x73,0x6F,0x6D,0x65,0x20, 00644 0x74,0x68,0x69,0x6E,0x67,0x73,0x21,0x20, 00645 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, 00646 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}; 00647 uint64_t* key = (uint64_t*)((int)sequence + 48); 00648 uint64_t* nonce = (uint64_t*)((int)sequence + 56); 00649 00650 uint8_t hash[32]; 00651 00652 orState = 0; //Rotot offset at motor state 0 00653 intState = 0; 00654 intStateOld = 0; 00655 00656 //Initialise PWM and Duty Cycle; 00657 PWM_pin.period(0.002f); 00658 PWM_pin.write(1.00f); 00659 00660 pc.printf("Hello\n\r"); 00661 00662 //Run the motor synchronisation 00663 orState = motorHome(); 00664 pc.printf("Rotor origin: %x\n\r",orState); 00665 00666 //orState is subtracted from future rotor state inputs to align rotor and motor states 00667 I1.rise(&Rotorcalib); 00668 I2.rise(&Rotorcalib); 00669 I3.rise(&Rotorcalib); 00670 I1.fall(&Rotorcalib); 00671 I2.fall(&Rotorcalib); 00672 I3.fall(&Rotorcalib); 00673 00674 hashRate = 0; 00675 t.start(); 00676 00677 printMsgT.start(callback(printMsgFn)); //start print msg thread 00678 readMsgT.start(callback(readMsgFn)); 00679 motorCtrlT.start(callback(motorCtrlFn)); // start the motorCtrlT thread 00680 00681 00682 while (1) { 00683 //testPin.write(!testPin.read()); 00684 newKey_mutex.lock(); 00685 *key = newKey; 00686 newKey_mutex.unlock(); 00687 00688 mySHA256.computeHash(hash,sequence,sizeof(sequence)); 00689 hashRate++; 00690 if(t.read() >= 1){ //if a second has passed 00691 t.stop(); 00692 t.reset(); 00693 t.start(); 00694 char msg[10]; 00695 strcpy(msg, "VELOCITY: "); 00696 put_msg_string(msg); 00697 put_msg_float(velocity); 00698 char msg2[10]; 00699 strcpy(msg2, "HASH RATE: "); 00700 put_msg_string(msg2); 00701 put_msg_int(hashRate); //hashes per second 00702 hashRate = 0; 00703 } 00704 if((hash[0] == 0) && (hash[1] == 0)){ 00705 char msg1[10]; 00706 strcpy(msg1, "SUCCESS: "); 00707 put_msg_string(msg1); 00708 put_msg_int(*nonce); 00709 } 00710 *nonce+=1; 00711 00712 } 00713 } 00714
Generated on Tue Jul 19 2022 09:02:44 by 1.7.2