An embedded device

Dependencies:   Crypto

main.cpp

Committer:
Olaffo
Date:
2019-03-21
Revision:
26:d3e69e507616
Parent:
25:ca5ccbf55b07

File content as of revision 26:d3e69e507616:

#include "mbed.h"
#include "Crypto.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 output pins   //Mask in output byte
#define L1Lpin D1           //0x01
#define L1Hpin A3           //0x02
#define L2Lpin D0           //0x04
#define L2Hpin A6           //0x08
#define L3Lpin D10          //0x10
#define L3Hpin D2           //0x20

#define PWMpin D9

//Motor current sense
#define MCSPpin A1
#define MCSNpin A0

//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       -   -   -
*/
//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

//Phase lead to make motor spin
int8_t lead = -2;  //2 for forwards, -2 for backwards

//Status LED
DigitalOut led1(LED1);

//Photointerrupter inputs
InterruptIn I1(I1pin);
InterruptIn I2(I2pin);
InterruptIn I3(I3pin);

//Motor Drive outputs
DigitalOut L1L(L1Lpin);
DigitalOut L1H(L1Hpin);
DigitalOut L2L(L2Lpin);
DigitalOut L2H(L2Hpin);
DigitalOut L3L(L3Lpin);
DigitalOut L3H(L3Hpin);
PwmOut d9 (PWMpin);

int8_t orState = 0;
//int8_t intState = 0;
//int8_t intStateOld = 0;
int32_t revoCounter = 0;    //Counts the number of revolutions
int32_t motorVelocity;
uint8_t mode = 6;
//Phase lead to make motor spin
//int8_t lead = -2;  //2 for forwards, -2 for backwards

typedef struct {
  int message;
  uint64_t data;
  float fdata;
} mail_t;

Mail<mail_t, 16> mail_box;
Thread commsIn(osPriorityNormal,1024);
Thread bitcointhread(osPriorityNormal,1024);
Thread motorCtrlT(osPriorityNormal,1024);
Thread commsOut(osPriorityNormal,1024);

RawSerial pc(SERIAL_TX, SERIAL_RX);
Queue<void, 8> inCharQ;
Mutex newKey_mutex;
uint64_t newKey = 0;

volatile float newRev;
volatile float maxSpeed = 90;
float pulseWidth;
float motorPosition_command;
float motorPosition;
//float pulseWidth;

void serialISR() {
    uint8_t newChar = pc.getc();
    inCharQ.put((void*) newChar);
}
/***************************************************************/
//The following block should be moved to a library, but I don't the time to figure this out atm.

//CommsOut.h

enum message_keys {
KEY_DECLINED    = 0,
ROTATION_CMD    = 1,
ROTATION_FF_CMD = 2,
MAX_SPEED_CMD   = 3, 
KEY_ECHO        = 4,
TUNE_CMD        = 5,
STANDARD        = 6,
FOREVER_FORWARD = 7,
LEAD            = 9,


INVALID_CMD     = 10, 
MOTOR_POS       = 11,
MOTOR_SPEED     = 12,
  

NONCE_DETECT    = 14,
ROTOR_ORG       = 15,

WELCOME         = 20


};

void putMessage(int message, uint64_t data = 0, float fdata=0){
    mail_t *mail = mail_box.alloc();
    mail->message = message;
    mail->data = data;
    mail->fdata = fdata;
    mail_box.put(mail);
}

void commsOutFunc() {
    while (true) {
        osEvent evt = mail_box.get();
        if (evt.status == osEventMail) {
            mail_t *mail = (mail_t*)evt.value.p;
            switch (mail->message) {
                case KEY_DECLINED :
                    pc.printf("Not a valid key!\n\r");
                    break;
                case ROTATION_CMD :
                    pc.printf("Rotation count: %3.2f\n\r", mail->fdata);
                    break; 
                case ROTATION_FF_CMD :
                    pc.printf("I will rotate forever...");
                    break; 
                case MAX_SPEED_CMD :
                    pc.printf("Max speed: %2.1f\n\r", mail->fdata); 
                    break;  
                case KEY_ECHO :
                    pc.printf("Received key: %016llx\n\r", mail->data);
                    break;  
                case TUNE_CMD :
                    pc.printf("Tune command!\n\r");
                    break;
                case INVALID_CMD :
                    pc.printf("Invalid command!\r\n");
                    break;
                case MOTOR_POS :
                    pc.printf("Motor position: %f\r\n", mail->fdata);
                    //pc.printf("{TIMEPLOT|%.2f|Motor Position}", mail->fdata);
                    break;
                case MOTOR_SPEED :
                    pc.printf("Motor speed: %f\r\n", mail->fdata);
                    break;
                case NONCE_DETECT :
                    pc.printf("Successful nonce: %016x\n\r", mail->data);
                    break;
                case WELCOME :
                    pc.printf("Hello Olaf\n\r");
                    break;
                case ROTOR_ORG :
                    pc.printf("Rotor origin: %x\n\r", orState);
                case LEAD :
                    pc.printf("Lead: %d\n\r\n\r", mail->data);
                    break;
                
            }
            mail_box.free(mail);
        }
    }          
}
//End of that block
/***************************************************************/

/***************************************************************/
//The following block should also be moved to a library, but I still don't the time to figure this out atm.

//CommsIn.h

void R_Decoder(char* command) {
    int8_t sign =1;
    uint8_t index = 1;
    int intValue = 0;
    float decimalValue = 0;
    
    // Check sign
    if (command[1] == '-'){
        sign = -1;
        index++;
        }
    // Take first digit
    if (command[index] > ('0'-1) && command[index] < (1 + '9')) {
        intValue = command[index] - '0';
        index++;
        } 
    else {
        putMessage(INVALID_CMD); 
        return;
        }
                
    //Try taking 2 more digits
    if (command[index] > ('0'-1) && command[index] < (1 + '9')) {
        intValue = intValue*10 + command[index] - '0';
        index++;
        }
    if (command[index] > ('0'-1) && command[index] < (1 + '9')) {
        intValue = intValue*10 + command[index] - '0';
        index++;
        }
    //Check for '.'
    if (command[index] == '.') {
        index++;
        //Check for decimals
        if (command[index] > ('0'-1) && command[index] < (1 + '9')) {
            decimalValue = (command[index] - '0')/10;
            index++;
        }
        if (command[index] > ('0'-1) && command[index] < (1 + '9')) {
            decimalValue = (decimalValue/10 + command[index] - '0')/10;
        }
    }
    decimalValue = (decimalValue + intValue) * sign;
    if (decimalValue == 0){
        mode = FOREVER_FORWARD;
        putMessage(ROTATION_FF_CMD);
        }
        else {
        newRev = decimalValue;
        putMessage(ROTATION_CMD,0,decimalValue);
        }
}         

void V_Decoder(char* command) {
    uint8_t index = 1;
    int intValue = 0;
    float decimalValue = 0;
    
    // Take first digit
    if (command[index] > ('0'-1) && command[index] < (1 + '9')) {
        intValue = command[index] - '0';
        index++;
        } 
    else {
        putMessage(INVALID_CMD); 
        return;
        }
                
    //Try taking 2 more digits
    if (command[index] > ('0'-1) && command[index] < (1 + '9')) {
        intValue = intValue*10 + command[index] - '0';
        index++;
        }
    if (command[index] > ('0'-1) && command[index] < (1 + '9')) {
        intValue = intValue*10 + command[index] - '0';
        index++;
        }
    //Check for '.'
    if (command[index] == '.') {
        index++;
        //Check for one decimal
        if (command[index] > ('0'-1) && command[index] < (1 + '9')) {
            decimalValue = (command[index] - '0')/10;
        }
    }
    decimalValue = (decimalValue + intValue);
    maxSpeed = decimalValue;
    putMessage(MAX_SPEED_CMD,0,decimalValue);
}

void commandProcessor() {
    pc.attach(&serialISR);
    char command[19];
    char* number;
    //char k;
    uint64_t receivedKey;
    uint8_t index = 0;
    while(1) {
        osEvent newEvent = inCharQ.get();
        uint8_t newChar = (uint8_t) newEvent.value.p;
        command[index] = newChar;
        index++;
        if (newChar == '\r') {    
            command[17] = '\0';
            
            if (command[0] == 'R') {
                R_Decoder(command);
                motorPosition_command = motorPosition;
            }
            else if (command[0] == 'V') {
                V_Decoder(command);
            }
            else if (command[0] == 'K') {
                if (index == 18){ // when index is 18 means you entered K and 16 digits
                    number = command +1;    //super bad solution, but I don't know how to work with strings in C
                    receivedKey = strtoull(number, NULL, 16);
                    putMessage(KEY_ECHO,receivedKey);
                    
                    newKey_mutex.lock();
                    newKey = receivedKey;
                    newKey_mutex.unlock();
                } else { 
                    putMessage(KEY_DECLINED);
                };                
            }
            else if (command[0] == 'T') {
                putMessage(TUNE_CMD);
            }
            memset(command, 0, sizeof(command));
            index = 0;
        } else {
            pc.printf("Current command: %s\n\r", command);      //Not sure how to go around this one cause it requires passing string
        }
    }
}

void bitcoin(){
     while(1) {
        SHA256 sha;
        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];
        
        Timer t;
        t.start();
        unsigned currentTime = 0;
        unsigned currentCount= 0;
        
        for (unsigned i = 0; i <= UINT_MAX;  i++) {
            (*nonce)++;
            newKey_mutex.lock();
            *key = newKey;
            newKey_mutex.unlock();
            sha.computeHash(hash, sequence, 64);
            if (hash[0] == 0 && hash[1] == 0) {
                //putMessage(nonce);
                pc.printf("Successful nonce: %016x\n\r", *nonce);
            }
            if ((unsigned) t.read() == currentTime) {
                 //pc.printf("Hash rate: %d\n\r", i - currentCount);
                 //pc.printf("Current key: %016llx\n\r", *key);
                 currentTime++;
                 currentCount = i;
            }
        }
        t.stop();
    }
}

 
 
//Set a given drive state
void motorOut(int8_t driveState, float pulseWidth){
    
    //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;

    
    //d9.write(1);     
    d9.pulsewidth_us(pulseWidth);
}
    
//Convert photointerrupter inputs to a rotor state
inline int8_t readRotorState(){
    return stateMap[I1 + 2*I2 + 4*I3];
}

int8_t motorHome() {
    //Put the motor in drive state 0 and wait for it to stabilize
    motorOut(0,pulseWidth);
    wait(2.0);
    return readRotorState();
}


// ISR to handle the updating of the motor position
void motorISR() {
    static int8_t oldRotorState;
    //orState is subtracted from future rotor state inputs to align rotor and motor states   
    
    int8_t rotorState = readRotorState();
    motorOut((rotorState-orState+lead+6)%6,pulseWidth); //+6 to make sure the remainder is positive
    if (rotorState - oldRotorState == 5) motorPosition --;
    else if (rotorState - oldRotorState == -5) motorPosition ++;
    else motorPosition += (rotorState - oldRotorState);
    //pc.printf ("motorpPosition %f\n\r", motorPosition);
    oldRotorState = rotorState;
}
/*void push() {
    intState = readRotorState();
    if (intState != intStateOld) {
        intStateOld = intState;
        motorOut((intState - orState + lead +6) % 6); //+6 to make sure the remainder is positive
    }
}*/
void motorCtrlTick(){
 motorCtrlT.signal_set(0x1);
 }
void motorCtrlFn(){
    int32_t counter=0;
    static int32_t oldmotorPosition;
    float Ts;
    float sError;      //speed error
    float intError = 0; //integral of velError
    float Tr;
    float error;
    float olderror = 0;
    float Speed;
    float Rev;
    int8_t leads = -2;
    int8_t leadr = -2;
    float kps = 25;
    float kis = 0.07;
    float kpr = 35;
    float kdr = 14.75; //proportional constant for speed
    // Timer to count time passed between ticks to calculate velocity
    Timer motorTime;
    motorTime.start();
    float motorPos;
    float myTime;
    
    Ticker motorCtrlTicker;
    motorCtrlTicker.attach_us(&motorCtrlTick,100000);
    while(1){
        motorCtrlT.signal_wait(0x1);

        // Convert variabls to int
        Speed = maxSpeed*6;
        Rev = newRev *6;
        motorPos = motorPosition;
        
        myTime = motorTime.read();
        motorVelocity = (motorPos - oldmotorPosition)/myTime;
        error = Rev + motorPosition_command - motorPos; 
        oldmotorPosition = motorPos;
        
        //equation for controls
        sError = Speed -abs(motorVelocity);
        if (motorVelocity != 0){
            intError = intError + sError;
        }
        Ts = (kps * sError + kis * intError)*(error/abs(error));
        Tr = kpr*error+kdr*(error-olderror)/ myTime;
        
        // Speed AND rotation control (aka standard mode)
        if (mode = STANDARD)
        {
            // Case for reverse rotation
            if (error < 0){
            
                // Case for choosing rotational control
                if (Ts <=Tr ){
                
                    // Flip lead
                    if      ( Tr >= 0) { lead = -2; }
                    else if ( Tr <  0) { lead = 2; }
                
                    // Assure torque is in bounds
                    if (Tr > 2000){ Tr = 2000; }
                    else if (Tr < 0){ Tr = -Tr; }
                    else if (Tr < -2000){ Tr = 2000; }
                
                    // Pass torque
                    pulseWidth = Tr;
                }
            
                // Case for choosing speed control
                else {
                    // Flip lead
                    if      ( Ts >= 0) { lead = -2; }
                    else if ( Ts <  0) { lead = 2; }
                
                    // Assure torque is in bounds
                    if (Ts > 2000){ Ts = 2000; }
                    else if (Ts < 0){ Ts = -Ts; }
                    else if (Ts < -2000){ Ts = 2000; }
                
                    // Pass torque
                    pulseWidth = Ts;
                }
            }
        
            // Case for forward rotation
            else if (error >= 0){
            
                // Case for choosing speed control
                if (Ts <=Tr ){
                    // Flip lead
                    if      ( Ts >= 0) { lead = -2; }
                    else if ( Ts <  0) { lead = 2; }
                
                    // Assure torque is in bounds
                    if (Ts > 2000){ Ts = 2000; }
                    else if (Ts < 0){ Ts = -Ts; }
                    else if (Ts < -2000){ Ts = 2000; }
                
                    // Pass torque
                    pulseWidth = Ts;
                }
            
                // Case for rotational speed control
                else {
                
                    // Flip lead
                    if      ( Tr >= 0) { lead = -2; }
                    else if ( Tr <  0) { lead = 2; }
                
                    // Assure torque is in bounds
                    if (Tr > 2000){ Tr = 2000; }
                    else if (Tr < 0){ Tr = -Tr; }
                    else if (Tr < -2000){ Tr = 2000; }
                
                    // Pass torque
                    pulseWidth = Tr;
                }
            }
        }
        
        
        // ONLY speed control (aka forever forward mode)
        else if (mode = FOREVER_FORWARD){
                
            if      ( Ts >= 0) { lead = -2; }
            else if ( Ts <  0) { lead = 2; }
                
            // Assure torque is in bounds
            if (Ts > 2000){ Ts = 2000; }
            else if (Ts < 0){ Ts = -Ts; }
            else if (Ts < -2000){ Ts = 2000; }
                
            pulseWidth = Ts;
            }
       
        counter++;
        motorTime.reset();
        // Serial output to monitor speed and position
        if(counter == 10){
            counter = 0;
            //display velocity and motor position 
            putMessage(MOTOR_POS,0,(float)(motorPosition/6.0));
            putMessage(MOTOR_SPEED,0,(float)(motorVelocity/6.0));
            putMessage(LEAD,lead);
        }
        olderror=error;
    }
}
int main() {    
    //Initialise bincoin mining and communication
    
    // Start up checkup
    d9.period(0.002f); //Set PWM period in seconds
    int8_t orState = motorHome();
    putMessage(WELCOME);
    putMessage(ROTOR_ORG);

    // Start all threads
    commsIn.start(commandProcessor);
    commsOut.start(commsOutFunc);
    motorCtrlT.start(motorCtrlFn);
    bitcointhread.start(bitcoin);
    
    // Define motor ISRs
    I1.rise(&motorISR);
    I2.rise(&motorISR);
    I3.rise(&motorISR);
    
    I1.fall(&motorISR);
    I2.fall(&motorISR);
    I3.fall(&motorISR);
   
   
}