123

Dependencies:   CPU_Usage DebounceIn QEI TFT_fonts UniGraphic

main.cpp

Committer:
turumputum
Date:
2018-08-06
Revision:
0:c049cebc31b4

File content as of revision 0:c049cebc31b4:

#include "mbed.h"
//#include "stdio.h"
#include "QEI.h"
#include "string"
#include "Arial12x12.h"
#include "Arial24x23.h"
#include "Arial28x28.h"
#include "font_big.h"
#include "bigFo.h"
#include "ILI9341.h"
#include "Arial43x48_numb.h"
#include "DebounceIn.h"
#include "CPU_Usage.h"



#define PI (3.141592653589793)

#define encoderRATE  100
#define lcdRATE  100
#define stepRATE  15

#define mmRatio  4450

#define stAngle  0
#define stFeed 1
#define stThread 2

#define editPos 0
#define editMult 1
#define editFeed 2

Timer t;

DigitalOut myled1(LED1);

Serial pc(USBTX, USBRX);


Thread threadEnc(osPriorityNormal);
Thread threadStep(osPriorityAboveNormal);

DebounceIn  wheelPanButton(PC_12);

DebounceIn  pos1Button(PB_12);
DebounceIn  pos2Button(PA_12);
DebounceIn  selectButton(PA_11);

InterruptIn  switch1Button(PC_8);
InterruptIn  switch2Button(PC_6);
InterruptIn  switch3Button(PC_5);
//PC_6 midle feed rubilnik pin


DigitalOut stepPin(PB_1);
DigitalOut dirPin(PB_2);


//Use X4 encoding.
//QEI wheel(p29, p30, NC, 624, QEI::X4_ENCODING);
//Use X2 encoding by default.
//QEI wheel (p29, p30, NC, 624);
QEI wheel (PB_13, PB_14, PB_15, 4000, QEI::X4_ENCODING);

QEI wheelPan (PC_11, PC_10, NC, 20, QEI::X4_ENCODING);

PinName buspins[8]={D8,D9,D2,D3,D4,D5,D6,D7};
ILI9341 myLCD(BUS_8, buspins, A3, A4, A2, A1, A0,"myLCD"); // Parallel Bus 8bit, buspins array, CS, reset, RS, WR, RD


unsigned short backgroundcolor=Blue;
unsigned short foregroundcolor=White;



int state=1, prevState=-1;

volatile int dir,z=1, k=7, edit=0;

volatile float stPos=0, stPrevPos=1, stTarget=0;
volatile float stepMult =1, prevStepMult=0, pos1, pos2, prevPos1, prevPos2;

float multMass[2]={0.1,1};
int feedMass[10]={30,60,120,180,240,300,450,600,900,1200};

volatile int Pulses     = 0, panPulses=0, feedRate = 450, delta;
volatile int PrevPulses = 0;
volatile int rev = 0;
volatile int prevRev = 0;
volatile int panAngle=0, prevPanAngle=0;
volatile float stepPeriod = stepRATE;
volatile float Angle = 0;
float prevAngle=0;
bool wheelBut, prevWheelBut, startUp=true, showStopPos=1;

    
void printWheelPan(){
    myLCD.set_font((unsigned char*) SCProSB31x55);
    myLCD.locate(50,50);
    myLCD.printf("%.1f ", Angle);
    myLCD.set_font((unsigned char*) Arial43x48_numb);
    myLCD.locate(50,50);
    myLCD.printf("%.1f ", Angle);
    }
    
void printWheelBut(){
    myLCD.set_font((unsigned char*) Arial24x23);
    myLCD.locate(150,50);
    myLCD.printf("But %.1i ", wheelBut);
    }
    
void printMult(){
    myLCD.set_font((unsigned char*) Arial24x23);
    myLCD.locate(90,215);
    myLCD.printf("%.1f", stepMult);
    }
    
void printFeed(){
    myLCD.set_font((unsigned char*) Arial24x23);
    myLCD.locate(250,215);
    myLCD.printf("%i", feedRate);
    }
    
void printTrPos(){
    myLCD.set_font((unsigned char*) Arial24x23);
    myLCD.locate(90,185);
    myLCD.printf("%.1f", pos1/mmRatio);
    }
    
void printPos2(){
    myLCD.set_font((unsigned char*) Arial24x23);
    myLCD.locate(250,185);
    myLCD.printf("%.1f", pos2/mmRatio);
    }
    
void printStPos(){
    myLCD.foreground(Green); 
    myLCD.set_font((unsigned char*) Arial12x12);
    myLCD.locate(10,95);
    float val=stTarget/mmRatio;
    myLCD.printf("%.1f ", val);
    myLCD.foreground(White); 
    myLCD.set_font((unsigned char*) SCProSB31x55);
    myLCD.locate(60,70);
    val=stPos/mmRatio;
    myLCD.printf("%.1f ", val);
    }


void printStAngle(){
    myLCD.cls();   
    myLCD.set_orientation(1);   
    myLCD.background(Blue);    // set background to black
    myLCD.foreground(White);    // set chars to white
    myLCD.rect(0,0,320,240, Blue);
    myLCD.set_font((unsigned char*) Arial28x28);
    myLCD.locate(100,10);
    myLCD.printf("ANGLE mode");
    myLCD.set_font((unsigned char*) Arial24x23);
    myLCD.locate(200,300);
    myLCD.printf("o");
    }
  //PRINT FEED MODE  
void printStFeed(){
    myLCD.cls();   
    myLCD.set_orientation(1);   
    myLCD.background(Blue);    // set background to black
    myLCD.foreground(White);    // set chars to white
    myLCD.rect(0,0,320,240, Blue);
    myLCD.set_font((unsigned char*) Arial28x28);
    myLCD.locate(75,10);
    myLCD.printf(" FEED mode");
    myLCD.background(Black);
    myLCD.set_font((unsigned char*) Arial24x23);
    myLCD.locate(5,70);
    myLCD.printf("pos ");
    myLCD.rect(0,180,160,210, Blue);
    myLCD.rect(160,180,320,210, Blue);
    myLCD.rect(160,210,320,240, Blue);
    myLCD.rect(0,210,160,240, Blue);
    myLCD.set_font((unsigned char*) Arial24x23);
    myLCD.locate(5,215);
    myLCD.printf("Mult:");
    myLCD.locate(165,215);
    myLCD.printf("Feed:");
    myLCD.locate(5,185);
    myLCD.printf("Pos1:");
    //myLCD.locate(165,185);
    //myLCD.printf("Pos2:");
    printFeed();
    }
    
void pitnTmpVar(float var){
    myLCD.set_font((unsigned char*) Arial12x12);
    myLCD.locate(5,5);
    myLCD.printf("%.1f ", var);
    }
    
void encoderPan_thread() {
    while(1){

        wheelBut=wheelPanButton.read();
        if(!wheelBut){
            int prevPanPulses=panPulses;
            panPulses=wheelPan.getPulses()/4;
            delta = (prevPanPulses - panPulses);
            if(edit==0){
                stTarget = stTarget+ (delta*stepMult*mmRatio);
            }else if(edit==1){
                z=z+delta;
                if(z>1){z=0;}else if (z<0){z=1;}
                stepMult= multMass[z]; 
            }else if(edit==2){
                k=k+delta;
                if(k>9){k=0;}else if (k<0){k=9;}
                feedRate = feedMass[k];
                stepPeriod=60000000/(feedRate*mmRatio);
            }
        }else{
            edit++;
            if(edit>2){edit=0;}
            wait_ms(100);
        }
        
        if(!pos1Button.read()){
            pos1=stPos;
            printTrPos();
            wait_ms(100);
        }
        
        if(!pos2Button.read()){
            stPos=0;
            stTarget = 0;
            printStPos();
            wait_ms(100);
        }
        
        if(!selectButton.read()){
            state++;
            if(state>1){state=0;}
            wait_ms(500);
        }
            
        wait_ms(encoderRATE);
        
    }
}

void feedToPos(){
    stepPeriod=60000000/(feedRate*mmRatio);
    stTarget = pos1;
    wait_ms(100);
}
void feedHandMode(){
    stepPeriod=stepRATE;
    wait_ms(100);
    }
void feedToZero(){
    stepPeriod=60000000/(feedRate*mmRatio);
    stTarget = 0;
    wait_ms(100);
    }


void stepper_thread() {
    while(1){
       if(stTarget>stPos){dirPin=1; dir=1;}else{dirPin=0;dir=-1;}
       
       if(stTarget!=stPos){
        stepPin=1;
        wait_us(2);
        stepPin=0;
        wait_us(stepPeriod);
        stPos=stPos+dir;
       } else{
           wait_ms(100);
           }
       
    }
}


int main() {
    pc.printf("startUp\r\n");  
    wheelPanButton.mode(PullUp);
    pos1Button.mode(PullUp);
    pos2Button.mode(PullUp);
    selectButton.mode(PullUp);
    switch1Button.mode(PullUp);
    switch2Button.mode(PullUp);
    switch3Button.mode(PullUp);
    pc.printf("ButtonIsPullUp\r\n");  
    
    switch1Button.fall(&feedToPos);
    switch2Button.fall(&feedHandMode);
    switch3Button.fall(&feedToZero);
    pc.printf("InteruptIsOn\r\n");  
    
    //wheelPanButton.set_samples(5);
    //wheelPanButton.set_debounce_us(5000);
    threadEnc.start(encoderPan_thread);
    pc.printf("encoderThreadIsRunning\r\n"); 
    wait_ms(500);
    threadStep.start(stepper_thread);
    pc.printf("stepperThreadIsRunning\r\n");  
    wait_ms(500);

    
    while(1){

        //ANGLE MODE    
        if ((state==stAngle)){
            //print screen
            if(state!=prevState){
                printStAngle();
                prevState=state;
            }
            if(prevAngle!=Angle){
                printWheelPan();
                prevAngle=Angle;
                stTarget = Angle*stepMult;
                }
                
            if(prevWheelBut!=wheelBut){
                //printWheelBut();
                prevWheelBut=wheelBut;
                }
            

        }
        //FEED MODE
        if ((state==stFeed)){
            //print screen
            if(state!=prevState){
                printStFeed();
                prevState=state;
            }
            //check encoder        
            if(stPrevPos!=stPos){
                printStPos();
                stPrevPos=stPos;
                showStopPos =1;
            }else if(showStopPos){
                printStPos();
                showStopPos=0; 
            }else if(edit==1){
                printMult();
            }else if(edit==2){
                printFeed();
            }
            

            
               
            if(prevStepMult!=stepMult){
                printMult();
                prevStepMult=stepMult;
            }
            
            
        }
        //pitnTmpVar(stepPeriod);
        wait_ms(lcdRATE);
    }

}