Summer 19 code

Dependencies:   wheelchaircontrol1

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers main.cpp Source File

main.cpp

00001 #include "wheelchair.h"
00002 
00003 QEI wheel (D10, D9, NC, 1200);        //Initializes right encoder
00004 DigitalIn pt3(D10, PullUp);          //Pull up resistors to read analog signals into digital signals
00005 DigitalIn pt4(D9, PullUp);
00006 
00007 /*added*/
00008 //DigitalIn e_button(D4);     //emergency button will start at HIGH
00009 
00010 QEI wheelS (D7, D8, NC, 1200);    //Initializes Left encoder
00011 DigitalIn pt1(D7, PullUp);          //Pull up resistors to read analog signals into digital signals
00012 DigitalIn pt2(D8, PullUp);
00013 
00014 int max_velocity;
00015 //Timer testAccT;
00016 
00017 AnalogIn x(A0);                     //Initializes analog axis for the joystick
00018 AnalogIn y(A1);
00019 
00020 double watchdogLimit = 0.1;             // Set timeout limit for watchdog timer in seconds
00021 int buttonCheck = 0;
00022 int iteration = 1;
00023 
00024 DigitalOut up(D12);                  //Turn up speed mode for joystick 
00025 DigitalOut down(D13);                //Turn down speed mode for joystick 
00026 DigitalOut on(D14);                 //Turn Wheelchair On
00027 DigitalOut off(D15);                //Turn Wheelchair Off
00028 bool manual = false;                //Turns chair joystic to automatic and viceverza
00029 
00030 Serial pc(USBTX, USBRX, 57600);     //Serial Monitor
00031 
00032 VL53L1X sensor1(PD_13, PD_12, PC_7);         //initializes ToF sensors
00033 VL53L1X sensor2(PD_13, PD_12, PA_15);
00034 VL53L1X sensor3(PD_13, PD_12, PB_5);
00035 VL53L1X sensor4(PD_13, PD_12, PF_14);
00036 VL53L1X sensor5(PD_13, PD_12, PE_11);
00037 VL53L1X sensor6(PD_13, PD_12, PE_13);
00038 VL53L1X sensor7(PD_13, PD_12, D6);
00039 VL53L1X sensor8(PD_13, PD_12, PE_12);
00040 VL53L1X sensor9(PD_13, PD_12, PE_10);
00041 VL53L1X sensor10(PD_13, PD_12, PE_15);
00042 VL53L1X sensor11(PD_13, PD_12, D6);
00043 VL53L1X sensor12(PB_11, PB_10, D11);
00044 
00045 VL53L1X* ToF[12] = {&sensor1, &sensor2, &sensor3, &sensor4, &sensor5, &sensor6, 
00046 &sensor7, &sensor8, &sensor9, &sensor10, &sensor11, &sensor12};                 //puts ToF sensor pointers into an array
00047 VL53L1X** ToFT = ToF;
00048 
00049 Timer t;                            //Initialize time object t
00050 EventQueue queue;                   //Class to organize threads
00051 Wheelchair smart(xDir,yDir, &pc, &t, &wheel, &wheelS, ToFT); //Initialize wheelchair object
00052 Thread compass;                      //Thread for compass
00053 Thread velocity;                      //Thread for velosity
00054 Thread assistSafe;                  //thread for safety stuff
00055 
00056 
00057 int main(void)
00058 {   
00059 /*    nh.initNode();
00060     nh.advertise(chatter);
00061     nh.advertise(chatter2);
00062     nh.subscribe(sub);*/
00063     //testAccT.start();
00064     pc.printf("before starting\r\n");
00065     //queue.call_every(SAMPLEFREQ, &smart, &Wheelchair::compass_thread);  //Sets up sampling frequency of the compass_thread
00066     queue.call_every(SAMPLEFREQ, &smart, &Wheelchair::velocity_thread); //Sets up sampling frequency of the velosity_thread
00067     queue.call_every(SAMPLEFREQ, &smart, &Wheelchair::assistSafe_thread); //Sets up sampling frequency of the velosity_thread
00068     //queue.call_every(200, rosCom_thread); //Sets up sampling frequency of the velosity_thread
00069     t.reset();
00070     //compass.start(callback(&queue, &EventQueue::dispatch_forever));      //Starts running the compass thread
00071     velocity.start(callback(&queue, &EventQueue::dispatch_forever));     //Starts running the velosity thread
00072     assistSafe.start(callback(&queue, &EventQueue::dispatch_forever));     //Starts running the velosity thread
00073     //ros_com.start(callback(&queue, &EventQueue::dispatch_forever));     //Starts running the velosity thread
00074         pc.printf("After starting\r\n");
00075 
00076     //added
00077  //   int emerg_button = e_button;
00078  
00079     int set = 0;
00080     while(1) {
00081         if( pc.readable()) {
00082             set = 1;
00083             char c = pc.getc();                                         //Read the instruction sent
00084             if( c == 'w') {
00085                 smart.forward();                                        //Move foward
00086 
00087             }
00088             else if( c == 'a') {
00089                 smart.left();                                           //Turn left
00090             }
00091             else if( c == 'd') {
00092                 smart.right();                                          //Turn right
00093             }
00094             else if( c == 's') {
00095                 smart.backward();                                       //Turn rackwards
00096             }
00097             
00098             else if( c == 't') {                                        
00099                 smart.pid_twistA();
00100             } else if(c == 'v'){
00101                 smart.showOdom();
00102             } else if(c == 'o') {                                       //Turns on chair
00103                 pc.printf("turning on\r\n");
00104                 on = 1;
00105                 wait(1);
00106                 on = 0;
00107             } else if(c == 'f') {                                       //Turns off chair
00108                 pc.printf("turning off\r\n");
00109                 off = 1;
00110                 wait(1);
00111                 off = 0;
00112             
00113             } else if(c == 'k'){                                        //Sends command to go to the kitchen
00114                 smart.pid_twistV();
00115             } else if( c == 'm' || manual) {                            //Turns wheelchair to joystick
00116                 pc.printf("turning on joystick\r\n");
00117                 manual = true;
00118                 t.reset();
00119                 while(manual) {
00120                     smart.move(x,y);                                    //Reads from joystick and moves
00121                     if( pc.readable()) {
00122                         char d = pc.getc();
00123                         if( d == 'm') {                                 //Turns wheelchair from joystick into auto
00124                             pc.printf("turning off joystick\r\n");
00125                             manual = false;
00126                         }
00127                     }
00128                 }   
00129             }
00130              else {
00131                     pc.printf("none \r\n");
00132                     smart.stop();                                      //If nothing else is happening stop the chair
00133             }
00134         }
00135         else {
00136             
00137             smart.stop();                                              //If nothing else is happening stop the chair
00138         }
00139         
00140         wait(process);
00141         
00142 /*        t.stop();
00143         pc.printf("Time elapsed: %f seconds and iteration = %d\n", t.read(), iteration);
00144         dog.Service();                                                  // Service the Watchdog so it does not cause a system reset - "Kicking"/"Feeding" the dog
00145     */
00146     }
00147 }
00148