Callum and Adel's changes on 12/02/19
Dependencies: Crypto
main.cpp
- Committer:
- iachinweze1
- Date:
- 2019-03-22
- Revision:
- 52:8339cd5c6105
- Parent:
- 46:b9081aa50bda
File content as of revision 52:8339cd5c6105:
/*TODO: Change: Indx newCmd _MAXCMDLENGTH move the global variables to a class because we arent paeasents - Mission Failed use jack's motor motor position fix class variable naming dont make everything public becuase thats fucling dumb and defeats the whole point of a class */ //Mapping from sequential drive states to motor phase outputs /* State L1 L2 L3 0 H - L 1 - H L 2 L H - 3 L - H 4 - L H 5 H L - 6 - - - 7 - - - */ //Header Files #include "SHA256.h" #include "mbed.h" //Photointerrupter Input Pins #define I1pin D3 #define I2pin D6 #define I3pin D5 //Incremental Encoder Input Pins #define CHApin D12 #define CHBpin D11 //Motor Drive High Pins //Mask in output byte #define L1Hpin A3 //0x02 #define L2Hpin A6 //0x08 #define L3Hpin D2 //0x20 //Motor Drive Low Pins #define L1Lpin D1 //0x01 #define L2Lpin D0 //0x04 #define L3Lpin D10 //0x10 //Motor Pulse Width Modulation (PWM) Pin #define PWMpin D9 //Motor current sense #define MCSPpin A1 #define MCSNpin A0 // "Lacros" for utility #define sgn(x) ((x)>=0?1:-1) #define max(x,y) ((x)>=(y)?(x):(y)) #define min(x,y) ((x)>=(y)?(y):(x)) //Status LED DigitalOut led1(LED1); //Photointerrupter Inputs InterruptIn I1(I1pin); InterruptIn I2(I2pin); InterruptIn I3(I3pin); //Motor Drive High Outputs DigitalOut L1H(L1Hpin); DigitalOut L2H(L2Hpin); DigitalOut L3H(L3Hpin); //Motor Drive Low Outputs DigitalOut L1L(L1Lpin); DigitalOut L2L(L2Lpin); DigitalOut L3L(L3Lpin); PwmOut pwmCtrl(PWMpin); //Drive state to output table const int8_t driveTable[] = {0x12,0x18,0x09,0x21,0x24,0x06,0x00,0x00}; //Mapping from interrupter inputs to sequential rotor states. 0x00 and 0x07 are not valid const int8_t stateMap[] = {0x07,0x05,0x03,0x04,0x01,0x00,0x02,0x07}; //const int8_t stateMap[] = {0x07,0x01,0x03,0x02,0x05,0x00,0x04,0x07}; //Alternative if phase order of input or drive is reversed class Comm{ public: volatile bool _outMining; volatile float _targetVel, _targetRot; volatile int8_t _modeBitField; // 0,0,0,... <=> Melody,Torque,Rotation,Velocity const uint8_t _MAXCMDLENGTH; // volatile uint8_t _inCharIndex, _cmdIndex; // volatile uint32_t _motorTorque; // Motor Toque volatile int32_t _motor_pos; volatile uint64_t _newKey; // hash key Mutex _newKeyMutex; // Restrict access to prevent deadlock. RawSerial _pc; Thread _t_comm_out; bool _RUN; enum msgType { motorState, posIn, velIn, posOut, velOut, hashRate, keyAdded, nonceMatch, torque, rotations, melody, error}; typedef struct { msgType type; uint32_t message; } msg; Mail<msg, 32> mailStack; //public: //--------- Default Constructor With Inheritance From RawSerial Constructor ---------// Comm(): _pc(SERIAL_TX, SERIAL_RX), _t_comm_out(osPriorityAboveNormal, 1024), _MAXCMDLENGTH(18){ _pc.printf("\n\r%s\n\r", "Welcome" ); // _MAXCMDLENGTH = 18; _pc.putc('>'); for (int i = 0; i < _MAXCMDLENGTH; ++i) { // reset buffer inCharQ[i] = (char)'.'; // MbedOS prints 'Embedded Systems are fun and do awesome things!' // _pc.putc('.'); // if you print a null terminator } inCharQ[_MAXCMDLENGTH] = (char)'\0'; sprintf(inCharQ, "%s", inCharQ); // sorts out the correct string correctly strncpy(newCmd, inCharQ, _MAXCMDLENGTH); _pc.printf("%s\n\r", inCharQ); _pc.putc('<'); //_pc.putc('\r'); _pc.putc('>'); _cmdIndex = 0; _inCharIndex = 0; _outMining = false; _pc.attach(callback(this, &Comm::serialISR)); _motorTorque = 300; _targetVel = 45.0; _targetRot = 459.0; _motor_pos = 0; _modeBitField = 0x01; // Default is velocity mode } //--------- Interrupt Service Routine for Serial Port and Character Queue Handling ---------// void serialISR(){ if (_pc.readable()) { char newChar = _pc.getc(); if (_inCharIndex == (_MAXCMDLENGTH)) { inCharQ[_MAXCMDLENGTH] = '\0'; // force the string to have an end character putMessage(error, 1); _inCharIndex = 0; // reset buffer index } else{ if(newChar != '\r'){ //While the command is not over, inCharQ[_inCharIndex] = newChar; //save input character and _inCharIndex++; //advance index _pc.putc(newChar); } else{ inCharQ[_inCharIndex] = '\0'; //When the command is finally over, strncpy(newCmd, inCharQ, _MAXCMDLENGTH); // Will copy 18 characters from inCharQ to newCmd cmdParser(); //parse the command for decoding. for (int i = 0; i < _MAXCMDLENGTH; ++i) // reset buffer inCharQ[i] = ' '; _inCharIndex = 0; // reset index } } } } //--------- Reset Cursor Position ---------// void returnCursor() { _pc.putc('>'); for (int i = 0; i < _inCharIndex; ++i) _pc.putc(inCharQ[i]); } //--------- Parse Incomming Data From Serial Port ---------// void cmdParser(){ switch(newCmd[0]) { case 'K': //keyAdded _newKeyMutex.lock(); //Ensure there is no deadlock sscanf(newCmd, "K%x", &_newKey); //Find desired the Key code putMessage(keyAdded, _newKey); //Print it out _newKeyMutex.unlock(); break; case 'V': //velIn sscanf(newCmd, "V%f", &_targetVel); //Find desired the target velocity _modeBitField = 0x01; //Adjust bitfield pos 1 _motor_pos = 0; putMessage(velIn, _targetVel); //Print it out break; case 'R': //posIn sscanf(newCmd, "R%f", &_targetRot); //Find desired target rotation _modeBitField = 0x02; //Adjust bitfield pos 2 _targetVel = 2e3; _motor_pos = 0; putMessage(posIn, _targetRot); //Print it out break; case 'x': //torque sscanf(newCmd, "x%u", &_motorTorque); //Find desired target torque _modeBitField = 0x04; //Adjust bitfield pos 3 putMessage(torque, _motorTorque); //Print it out break; case 'M': //mining display toggle int8_t miningTest; sscanf(newCmd, "M%d", &miningTest); //display if input is 1 if (miningTest == 1) _outMining = true; else _outMining = false; break; // This guy ugly, maybe use a function case 'T': // Tune/ melody uint8_t dur[9]; // Note Durations char notes[9]; // Actual notes uint8_t len = 0; // Length of notes for (int i = 1; i < _MAXCMDLENGTH; ++i) { // Find first # if (newCmd[i] == '#') { len = i; break; // stop at first # found } } if (len>0) { // Parse the input only if # found uint8_t newLen = 2*(len+1)+1; bool isChar = true; char formatSpec[newLen]; formatSpec[0]='T'; for (int i = 1; i < newLen; i=i+2) { // Create a format spec based on length of input formatSpec[i] = '%'; if (isChar) // if character formatSpec[i+1] = 'c'; else formatSpec[i+1] = 'u'; isChar = !isChar; } formatSpec[newLen] = '\0'; sprintf(formatSpec, "%s", formatSpec); // Set string format correctly _pc.printf("%s\n", formatSpec ); sscanf(newCmd, formatSpec, ¬es[0], &dur[0], ¬es[1], &dur[1], ¬es[2], &dur[2], ¬es[3], &dur[3], ¬es[4], &dur[4], ¬es[5], &dur[5], ¬es[6], &dur[6], ¬es[7], &dur[7], ¬es[8], &dur[8] ); _modeBitField = 0x08; // putMessage(melody, newCmd); //Print it out _pc.printf(formatSpec, notes[0], dur[0], \ notes[1], dur[1], \ notes[2], dur[2], \ notes[3], dur[3], \ notes[4], dur[4], \ notes[5], dur[5], \ notes[6], dur[6], \ notes[7], dur[7], \ notes[8], dur[8] \ ); } else putMessage(error, 2); // bad times break; break; default: break; } } //--------- Decode Messages to Print on Serial Port ---------// void commOutFn() { while (_RUN) { osEvent newEvent = mailStack.get(); msg *pMessage = (msg *) newEvent.value.p; //Case Switch to Choose Serial Output Based on Incoming Message Enum switch (pMessage->type) { case motorState: _pc.printf("\r>%s< The motor is currently in state %x\n\r", inCharQ, pMessage->message); break; case hashRate: if (_outMining) { _pc.printf("\r>%s< Mining: %.4u Hash/s\r", inCharQ, (uint32_t) pMessage->message); returnCursor(); _outMining = false; } break; case nonceMatch: _pc.printf("\r>%s< Nonce found: %x\n\r", inCharQ, pMessage->message); returnCursor(); break; case keyAdded: _pc.printf("\r>%s< New Key Added:\t0x%016x\n\r", inCharQ, pMessage->message); break; case torque: _pc.printf("\r>%s< Motor Torque set to:\t%d\n\r", inCharQ, (int32_t) pMessage->message); break; case velIn: _pc.printf("\r>%s< Target Velocity set to:\t%.2f\n\r", inCharQ, _targetVel); break; case velOut: _pc.printf("\r>%s< Current Velocity:\t%.2f States/sec\n\r", inCharQ, (float) ((int32_t) pMessage->message)); break; case posIn: _pc.printf("\r>%s< Target # Rotations:\t%.2f\n\r", inCharQ, (float) ((int32_t) pMessage->message)); break; case posOut: _pc.printf("\r>%s< Current Position:\t%.2f\n\r", inCharQ, (float) ((int32_t) pMessage->message /*/ 6*/)); break; case error: _pc.printf("\r>%s< Debugging position:%x\n\r", inCharQ, pMessage->message); for (int i = 0; i < _MAXCMDLENGTH; ++i) // reset buffer inCharQ[i] = ' '; break; default: _pc.printf("\r>%s< Unknown Error. Message: %x\n\r", inCharQ, pMessage->message); break; } mailStack.free(pMessage); } } void putMessage(msgType type, uint32_t message){ msg *p_msg = mailStack.alloc(); p_msg->type = type; p_msg->message = message; mailStack.put(p_msg); } void start_comm(){ _RUN = true; // for (int i = 0; i < _MAXCMDLENGTH; ++i) { // reset buffer // inCharQ[i] = (char)'.'; // MbedOS prints 'Embedded Systems are fun and do awesome things!' // } // inCharQ[_MAXCMDLENGTH] = (char)'\0'; // sprintf(inCharQ, "%s", inCharQ); // sorts out the correct string correctly // strncpy(newCmd, inCharQ, _MAXCMDLENGTH); _t_comm_out.start(callback(this, &Comm::commOutFn)); } char newCmd[]; // because unallocated must be defined at the bottom of the class static char inCharQ[]; }; char Comm::inCharQ[] = {'.','.','.','.','.','.','.','.','.','.','.','.','.','.','.','.','.','\0'}; class Motor { protected: int8_t orState; //Rotor offset at motor state 0, motor specific volatile int8_t currentState; //Current Rotor State volatile int8_t stateList[6]; //All possible rotor states stored int8_t old_rotor_state; //Phase lead to make motor spin volatile int8_t lead; Comm* p_comm; bool _RUN; //Run the motor synchronisation float dutyC; // 1 = 100% uint32_t mtrPeriod; // motor period uint8_t stateCount[3]; // State Counter uint8_t theStates[3]; // The Key states Thread t_motor_ctrl; // Thread for motor Control uint32_t MAXPWM_PRD; uint32_t MINPWM_PRD; public: Motor() : t_motor_ctrl(osPriorityAboveNormal2, 2048) { // Set Power to maximum to drive motorHome() dutyC = 1.0f; mtrPeriod = 2e3; // motor period pwmCtrl.period_us(mtrPeriod); pwmCtrl.pulsewidth_us(mtrPeriod); orState = motorHome(); // Rotor offset at motor state 0 currentState = readRotorState(); // Current Rotor State old_rotor_state = orState; // Set old_rotor_state to the origin to begin with // stateList[6] = {0,0,0, 0,0,0}; //All possible rotor states stored lead = 2; //2 for forwards, -2 for backwards // It skips the origin state and it's 'lead' increments? theStates[0] = orState +1; theStates[1] = (orState + lead) % 6 +1; theStates[2] = (orState + (lead*2)) % 6 +1; stateCount[0] = 0; stateCount[1] = 0; stateCount[2] = 0; p_comm = NULL; // null pointer for now _RUN = false; MAXPWM_PRD = 2e3; } int findMinTorque() { int8_t prevState = readRotorState(); uint32_t mtPeriod = 700; Timer testTimer; testTimer.start(); p_comm->_pc.printf("PState:%i, CState:%i\n", prevState, readRotorState()); // stateUpdate(); while (readRotorState() == prevState) { testTimer.reset(); // pwmCtrl.period_us(2e3); pwmCtrl.pulsewidth_us(mtPeriod); stateUpdate(); while (testTimer.read_ms() < 500) {} // prevState = readRotorState(); mtPeriod += 10; mtPeriod = mtrPeriod >= 1000 ? 700 : mtPeriod; } p_comm->_pc.printf("Min Torque:%i\n", mtPeriod); return mtPeriod; } void motorStart(Comm *comm) { // Establish Photointerrupter Service Routines (auto choose next state) I1.fall(callback(this, &Motor::stateUpdate)); I2.fall(callback(this, &Motor::stateUpdate)); I3.fall(callback(this, &Motor::stateUpdate)); I1.rise(callback(this, &Motor::stateUpdate)); I2.rise(callback(this, &Motor::stateUpdate)); I3.rise(callback(this, &Motor::stateUpdate)); // push digitally so if motor is static it will start moving motorOut((currentState-orState+lead+6)%6); // We push it digitally // Default a lower duty cycle dutyC = 0.8; pwmCtrl.period_us((uint32_t)mtrPeriod); pwmCtrl.pulsewidth_us((uint32_t)mtrPeriod*dutyC); p_comm = comm; // TODO: Make a better findMinTorque() function // MINPWM_PRD = findMinTorque(); MINPWM_PRD = 920; _RUN = true; // Start motor control thread t_motor_ctrl.start(callback(this, &Motor::motorCtrlFn)); p_comm->_pc.printf("origin=%i, theStates=[%i,%i,%i]\n\r", orState, theStates[0], theStates[1], theStates[2]); } //Set a given drive state void motorOut(int8_t driveState) { //Lookup the output byte from the drive state. int8_t driveOut = driveTable[driveState & 0x07]; //Turn off first if (~driveOut & 0x01) L1L = 0; if (~driveOut & 0x02) L1H = 1; if (~driveOut & 0x04) L2L = 0; if (~driveOut & 0x08) L2H = 1; if (~driveOut & 0x10) L3L = 0; if (~driveOut & 0x20) L3H = 1; //Then turn on if (driveOut & 0x01) L1L = 1; if (driveOut & 0x02) L1H = 0; if (driveOut & 0x04) L2L = 1; if (driveOut & 0x08) L2H = 0; if (driveOut & 0x10) L3L = 1; if (driveOut & 0x20) L3H = 0; } //Convert photointerrupter inputs to a rotor state inline int8_t readRotorState() { return stateMap[I1 + 2*I2 + 4*I3]; } //Basic synchronisation routine int8_t motorHome() { //Put the motor in drive state 0 and wait for it to stabilise motorOut(0); wait(3.0); //Get the rotor state return readRotorState(); } void stateUpdate() { // () { // **params currentState = readRotorState(); // (Current - Offset + lead + 6) %6 motorOut((currentState - orState + lead + 6) % 6); if (currentState - old_rotor_state == 5) { p_comm->_motor_pos--; } else if (currentState - old_rotor_state == -5) { p_comm->_motor_pos++; } else { p_comm->_motor_pos += (currentState - old_rotor_state); } old_rotor_state = currentState; } // attach_us -> runs funtion every 100ms void motorCtrlFn() { Ticker motorCtrlTicker; Timer m_timer; motorCtrlTicker.attach_us(callback(this,&Motor::motorCtrlTick), 1e5); // Init some things uint8_t cpyStateCount[3]; uint8_t cpyCurrentState; int8_t cpyModeBitfield; int32_t ting[2] = {6,1}; // 360,60 (for degrees), 5,1 (for states) uint8_t iterElementMax; int32_t totalDegrees; int32_t stateDiff; volatile int32_t torque; //Local variable to set motor torque static int32_t oldTorque = 0; float sError; //Velocity error between target and reality float rError; //Rotation error between target and reality static float rErrorOld; //Old rotation error used for calculation //~~~Controller constants~~~~ int32_t Kp1=80; //22, 27 //Proportional controller constants int32_t Kp2=33; //12 //Calculated by trial and error to give optimal accuracy float Kis = 0.0f; // 50 int32_t Kir = 0.0f; float sIntegral = 0.0f; float rIntegral = 0.0f; float Kd =28.5; // 40, 14.75 int32_t Ys; //Initialise controller output Ys (s=speed) int32_t Yr; //Initialise controller output Yr (r=rotations) int32_t old_pos = 0, cur_pos = 0; float cur_err = 0.0f, old_err = 0.0f, err_diff, time_diff, cur_time = 0.0f, old_time = 0.0f, cur_speed = 0.0f; //Variable for local velocity calculation; m_timer.start(); while (_RUN) { t_motor_ctrl.signal_wait((int32_t)0x1); core_util_critical_section_enter(); cpyModeBitfield = p_comm->_modeBitField; // p_comm->_modeBitField = 0; // nah //Access shared variables here /* std::copy(stateCount, stateCount+3, cpyStateCount); cpyCurrentState = currentState; for (int i = 0; i < 3; ++i) { stateCount[i] = 0; } */ // p_comm->_pc.printf("R_Error: %f\n", rError); core_util_critical_section_exit(); // p_comm->_pc.printf("BitField:%#04x\n", cpyModeBitfield); // read state & timestamp cur_pos = p_comm->_motor_pos; if (cur_pos < 2) { rIntegral = 0.0f; sIntegral = 0.0f; } cur_time = m_timer.read(); // compute speed time_diff = cur_time - old_time; cur_speed = (cur_pos - old_pos) / time_diff; // prep values for next time through loop old_time = cur_time; old_pos = cur_pos; // Position error rError = (p_comm->_targetRot) - (cur_pos/6.0f); if ((cur_speed != 0)) { rIntegral += rError * time_diff; } err_diff = rError - old_err; old_err = rError; // Speed error - Convert curr_speed from states per time to rotations per time // TODO: Check the direction that CPos goes in when _targetVel < 0 sError = (p_comm->_targetVel) - (abs(cur_speed/6.0f)); //Read global variable _targetVel updated by interrupt and calculate error between target and reality if ((cur_speed > 0) && (torque != MAXPWM_PRD)) { sIntegral += sError * time_diff; } Ys = (int32_t)(((Kp1 * sError) + (Kis * sIntegral))); // * sgn(cur_pos)); Yr = (int32_t)(Kp2*rError + ((Kd/time_diff) * err_diff) + (Kir * rIntegral)); if (cpyModeBitfield & 0x01) { // Speed control if (p_comm->_targetVel == 0) { //Check if user entered V0, torque = MAXPWM_PRD; //and set the output to maximum as specified } else { // select minimum absolute value torque if (cur_speed < 0) { torque = max(Ys, Yr); } else { torque = min(Ys, Yr); } torque = abs(torque) < MINPWM_PRD ? MINPWM_PRD*sgn(torque) : torque; // torque = Ys; } } else if (cpyModeBitfield & 0x02) { // select minimum absolute value torque if (p_comm->_targetRot == 0) { // Not spinning at max speed torque = 0.7 * MAXPWM_PRD; } else { /* // TODO: Handle sign or Yr for negative rotations if (Yr > MINPWM_PRD || Yr < 100) { torque = Yr; } else if (Yr >= 100 && Yr <= MINPWM_PRD) { torque = MINPWM_PRD; } */ // select minimum absolute value torque if (cur_speed < 0) { torque = max(Ys, Yr); } else { torque = min(Ys, Yr); } if (abs(rError) > 0.8) { // torque = abs(Yr) < 1000 ? 1000*sgn(Yr) : Yr; torque = abs(torque) < MINPWM_PRD ? MINPWM_PRD*sgn(torque) : torque; } else { torque = 0; } } } // iterElementMax = std::max_element(cpyStateCount, cpyStateCount+3) - cpyStateCount; /* // if ((cpyModeBitfield & 0x01) | (cpyModeBitfield & 0x02)) { if (cpyModeBitfield & 0x01) { // Speed error - Convert curr_speed from states per time to rotations per time sError = (p_comm->_targetVel) - (abs(cur_speed/6.0f)); //Read global variable _targetVel updated by interrupt and calculate error between target and reality //~~~~~Speed control~~~~~~ if (p_comm->_targetVel == 0) { //Check if user entered V0, torque = MAXPWM_PRD; //and set the output to maximum as specified } else { Ys = (int32_t)((Kp1 * sError) + Ki*(sError * time_diff)) * sgn(cur_pos); //If the user didn't enter V0 implement controller transfer function: Ys = Kp * (s -|v|) where, torque = Ys; } if (abs(sError) < 3) { // torque = torque; p_comm->_pc.printf("Final Speed:%f\n", cur_speed); } } else if (cpyModeBitfield & 0x02) { //~~~~~Rotation control~~~~~~ if (p_comm->_targetRot == 0) { // Not spinning at max speed torque = 0.7 * MAXPWM_PRD; } else { Yr = Kp2*rError + (Kd/time_diff) * err_diff; torque = abs(rError) < 3 ? 0 : Yr; } } if (cpyModeBitfield & 0x04) { // if it is in torque mode, do no math, just set pulsewidth torque = (int32_t)p_comm->_motorTorque; if (oldTorque != torque) { if(torque < 0) { // Variable torque cannot be negative since it sets the PWM torque = -torque; // Hence we make the value positive, lead = -2; // and instead set the direction to the opposite one } else { lead = 2; } if(torque > MAXPWM_PRD){ // In case the calculated PWM is higher than our maximum 50% allowance, torque = MAXPWM_PRD; // Set it to our max. } p_comm->putMessage((Comm::msgType)8, torque); p_comm->_motorTorque = torque; pwmCtrl.pulsewidth_us(torque); oldTorque = torque; } } */ if (torque < 0) { torque = -torque; lead = -2; } else { lead = 2; } torque = torque > MAXPWM_PRD ? MAXPWM_PRD : torque; // Set a cap on torque p_comm->_motorTorque = torque; pwmCtrl.pulsewidth_us(torque); p_comm->_pc.printf("RError:%.4f, SError:%.4f, CPos:%i, CSpeed:%f, Torque:%i, SInt:%f\r\n", rError, sError, cur_pos, (cur_speed/6.0f), torque, sIntegral); // Give the motor a kick stateUpdate(); } } void motorCtrlTick(){ t_motor_ctrl.signal_set(0x1); } }; int main() { // Declare Objects Comm comm_port; SHA256 miner; Motor motor; // Start Motor and Comm Port motor.motorStart(&comm_port); comm_port.start_comm(); // Declare Hash Variables uint8_t sequence[] = {0x45,0x6D,0x62,0x65,0x64,0x64,0x65,0x64, 0x20,0x53,0x79,0x73,0x74,0x65,0x6D,0x73, 0x20,0x61,0x72,0x65,0x20,0x66,0x75,0x6E, 0x20,0x61,0x6E,0x64,0x20,0x64,0x6F,0x20, 0x61,0x77,0x65,0x73,0x6F,0x6D,0x65,0x20, 0x74,0x68,0x69,0x6E,0x67,0x73,0x21,0x20, 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}; uint64_t* key = (uint64_t*)((int)sequence + 48); uint64_t* nonce = (uint64_t*)((int)sequence + 56); uint8_t hash[32]; uint32_t length64 = 64; uint32_t hashCounter = 0; // Begin Main Timer Timer timer; timer.start(); // Loop Program while (1) { // Mutex For Access Control comm_port._newKeyMutex.lock(); *key = comm_port._newKey; comm_port._newKeyMutex.unlock(); // Compute Hash and Counter miner.computeHash(hash, sequence, length64); hashCounter++; // Enum Casting and Condition if ((hash[0]==0) && (hash[1]==0)){ comm_port.putMessage((Comm::msgType)7, *nonce); } // Try Nonce (*nonce)++; // Display via Comm Port if (timer.read() >= 1){ comm_port.putMessage((Comm::msgType)5, hashCounter); hashCounter=0; timer.reset(); } } return 0; }