real time control for wheelchair with interupt

Dependencies:   wheelchaircontrol

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers main.cpp Source File

main.cpp

00001 #include "wheelchair.h"
00002 
00003 AnalogIn x(A0);
00004 AnalogIn y(A1);
00005 
00006 DigitalOut up(D2);
00007 DigitalOut down(D3);
00008 DigitalOut on(D12);
00009 DigitalOut off(D11);
00010 
00011 bool manual = false;
00012 
00013 Serial pc(USBTX, USBRX, 57600);
00014 
00015 Timer t;
00016 EventQueue queue;
00017 
00018 //MPU9250 imu(D14, D15);
00019 Wheelchair smart(xDir,yDir, &pc, &t);
00020 Thread thread;
00021 
00022 
00023 int main(void)
00024 {
00025     queue.call_every(SAMPLEFREQ, &smart, &Wheelchair::compass_thread);
00026     t.reset();
00027     thread.start(callback(&queue, &EventQueue::dispatch_forever));
00028     while(1) {
00029         if( pc.readable()) {
00030             char c = pc.getc();
00031 
00032             if( c == 'w') {
00033                 pc.printf("up \n");
00034                 smart.forward();
00035             }
00036 
00037             else if( c == 'a') {
00038                 //pc.printf("left \n");
00039                 smart.left();
00040             }
00041 
00042             else if( c == 'd') {
00043                 //pc.printf("right \n");
00044                 smart.right();
00045             }
00046 
00047             else if( c == 's') {
00048                 pc.printf("down \n");
00049                 smart.backward();
00050             }
00051 
00052             else if( c == 'r') {
00053                 smart.turn_right(90);
00054             }
00055 
00056             else if( c == 'l') {
00057                 smart.turn_left(90);
00058             }
00059 
00060             else if( c == 't') {
00061                 char buffer[256];
00062                 pc.printf ("Enter a long number: ");
00063                 fgets (buffer, 256, stdin);
00064                 int angle = atoi (buffer);
00065 
00066                 if(angle == 0) {
00067                     pc.printf("invalid input try again\n");
00068                 } else {
00069                     smart.pid_turn(angle);
00070                 }
00071 
00072             } else if(c == 'o') {
00073                 pc.printf("turning on\n");
00074                 on = 1;
00075                 wait(1);
00076                 on = 0;
00077             } else if(c == 'f') {
00078                 pc.printf("turning off\n");
00079                 off = 1;
00080                 wait(1);
00081                 off = 0;
00082             } else if( c == 'm' || manual) {
00083                 pc.printf("turning on joystick\n");
00084                 manual = true;
00085                 t.reset();
00086                 while(manual) {
00087                     smart.move(x,y);
00088                     if( pc.readable()) {
00089                         char d = pc.getc();
00090                         if( d == 'm') {
00091                             pc.printf("turning off joystick\n");
00092                             manual = false;
00093                         }
00094                     }
00095                 }
00096             }
00097 
00098             else {
00099                 pc.printf("none \n");
00100                 smart.stop();
00101             }
00102         }
00103 
00104         else {
00105             //        pc.printf("Nothing pressed \n");
00106             smart.stop();
00107         }
00108         wait(process);
00109     }
00110 
00111 }
00112 
00113 
00114 
00115 
00116