Integrated, working file (e-button and watchdog not integrated yet)
Dependencies: Watchdog
main.cpp@10:b5f6337c3a20, 2019-06-26 (annotated)
- Committer:
- JesiMiranda
- Date:
- Wed Jun 26 04:21:41 2019 +0000
- Revision:
- 10:b5f6337c3a20
- Parent:
- 9:ca11e4db63a7
Integrated working file (e-button, and watchdog not integrated yet)
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
ryanlin97 | 0:7e6b349182bc | 1 | #include "wheelchair.h" |
ryanlin97 | 0:7e6b349182bc | 2 | |
JesiMiranda | 10:b5f6337c3a20 | 3 | |
jvfausto | 9:ca11e4db63a7 | 4 | QEI wheel (D10, D9, NC, 1200); //Initializes right encoder |
jvfausto | 9:ca11e4db63a7 | 5 | DigitalIn pt3(D10, PullUp); //Pull up resistors to read analog signals into digital signals |
jvfausto | 9:ca11e4db63a7 | 6 | DigitalIn pt4(D9, PullUp); |
jvfausto | 9:ca11e4db63a7 | 7 | |
JesiMiranda | 10:b5f6337c3a20 | 8 | |
jvfausto | 9:ca11e4db63a7 | 9 | /*added*/ |
jvfausto | 9:ca11e4db63a7 | 10 | //DigitalIn e_button(D4); //emergency button will start at HIGH |
jvfausto | 8:db780b392bae | 11 | |
jvfausto | 9:ca11e4db63a7 | 12 | QEI wheelS (D7, D8, NC, 1200); //Initializes Left encoder |
jvfausto | 9:ca11e4db63a7 | 13 | DigitalIn pt1(D7, PullUp); //Pull up resistors to read analog signals into digital signals |
jvfausto | 9:ca11e4db63a7 | 14 | DigitalIn pt2(D8, PullUp); |
jvfausto | 8:db780b392bae | 15 | |
jvfausto | 9:ca11e4db63a7 | 16 | int max_velocity; |
jvfausto | 9:ca11e4db63a7 | 17 | //Timer testAccT; |
jvfausto | 9:ca11e4db63a7 | 18 | |
jvfausto | 9:ca11e4db63a7 | 19 | AnalogIn x(A0); //Initializes analog axis for the joystick |
ryanlin97 | 0:7e6b349182bc | 20 | AnalogIn y(A1); |
ryanlin97 | 0:7e6b349182bc | 21 | |
jvfausto | 9:ca11e4db63a7 | 22 | DigitalOut up(D12); //Turn up speed mode for joystick |
jvfausto | 9:ca11e4db63a7 | 23 | DigitalOut down(D13); //Turn down speed mode for joystick |
jvfausto | 9:ca11e4db63a7 | 24 | DigitalOut on(D14); //Turn Wheelchair On |
jvfausto | 9:ca11e4db63a7 | 25 | DigitalOut off(D15); //Turn Wheelchair Off |
jvfausto | 9:ca11e4db63a7 | 26 | bool manual = false; //Turns chair joystic to automatic and viceverza |
jvfausto | 9:ca11e4db63a7 | 27 | |
jvfausto | 9:ca11e4db63a7 | 28 | Serial pc(USBTX, USBRX, 57600); //Serial Monitor |
ryanlin97 | 0:7e6b349182bc | 29 | |
jvfausto | 9:ca11e4db63a7 | 30 | VL53L1X sensor1(PB_11, PB_10, D0); //initializes ToF sensors |
jvfausto | 9:ca11e4db63a7 | 31 | VL53L1X sensor2(PB_11, PB_10, D1); |
jvfausto | 9:ca11e4db63a7 | 32 | VL53L1X sensor3(PB_11, PB_10, D2); |
jvfausto | 9:ca11e4db63a7 | 33 | VL53L1X sensor4(PB_11, PB_10, D3); |
jvfausto | 9:ca11e4db63a7 | 34 | VL53L1X sensor5(PB_11, PB_10, D4); |
jvfausto | 9:ca11e4db63a7 | 35 | VL53L1X sensor6(PB_11, PB_10, D5); |
jvfausto | 9:ca11e4db63a7 | 36 | VL53L1X sensor7(PB_11, PB_10, PE_14); |
jvfausto | 9:ca11e4db63a7 | 37 | VL53L1X sensor8(PB_11, PB_10, PE_12); |
jvfausto | 9:ca11e4db63a7 | 38 | VL53L1X sensor9(PB_11, PB_10, PE_10); |
jvfausto | 9:ca11e4db63a7 | 39 | VL53L1X sensor10(PB_11, PB_10, PE_15); |
jvfausto | 9:ca11e4db63a7 | 40 | VL53L1X sensor11(PB_11, PB_10, D6); |
jvfausto | 9:ca11e4db63a7 | 41 | VL53L1X sensor12(PB_11, PB_10, D11); |
ryanlin97 | 5:90bf5f0d86e9 | 42 | |
jvfausto | 9:ca11e4db63a7 | 43 | VL53L1X* ToF[12] = {&sensor1, &sensor2, &sensor3, &sensor4, &sensor5, &sensor6, |
jvfausto | 9:ca11e4db63a7 | 44 | &sensor7, &sensor8, &sensor9, &sensor10, &sensor11, &sensor12}; //puts ToF sensor pointers into an array |
jvfausto | 9:ca11e4db63a7 | 45 | VL53L1X** ToFT = ToF; |
ryanlin97 | 0:7e6b349182bc | 46 | |
jvfausto | 9:ca11e4db63a7 | 47 | Timer t; //Initialize time object t |
jvfausto | 9:ca11e4db63a7 | 48 | EventQueue queue; //Class to organize threads |
jvfausto | 9:ca11e4db63a7 | 49 | Wheelchair smart(xDir,yDir, &pc, &t, &wheel, &wheelS, ToFT); //Initialize wheelchair object |
jvfausto | 9:ca11e4db63a7 | 50 | Thread compass; //Thread for compass |
jvfausto | 9:ca11e4db63a7 | 51 | Thread velocity; //Thread for velosity |
jvfausto | 9:ca11e4db63a7 | 52 | Thread assistSafe; //thread for safety stuff |
ryanlin97 | 0:7e6b349182bc | 53 | |
ryanlin97 | 5:90bf5f0d86e9 | 54 | |
ryanlin97 | 0:7e6b349182bc | 55 | int main(void) |
jvfausto | 9:ca11e4db63a7 | 56 | { |
jvfausto | 9:ca11e4db63a7 | 57 | /* nh.initNode(); |
jvfausto | 9:ca11e4db63a7 | 58 | nh.advertise(chatter); |
jvfausto | 9:ca11e4db63a7 | 59 | nh.advertise(chatter2); |
jvfausto | 9:ca11e4db63a7 | 60 | nh.subscribe(sub);*/ |
jvfausto | 9:ca11e4db63a7 | 61 | //testAccT.start(); |
jvfausto | 9:ca11e4db63a7 | 62 | pc.printf("before starting\r\n"); |
jvfausto | 9:ca11e4db63a7 | 63 | queue.call_every(SAMPLEFREQ, &smart, &Wheelchair::compass_thread); //Sets up sampling frequency of the compass_thread |
jvfausto | 9:ca11e4db63a7 | 64 | queue.call_every(SAMPLEFREQ, &smart, &Wheelchair::velocity_thread); //Sets up sampling frequency of the velosity_thread |
jvfausto | 9:ca11e4db63a7 | 65 | queue.call_every(SAMPLEFREQ, &smart, &Wheelchair::assistSafe_thread); //Sets up sampling frequency of the velosity_thread |
jvfausto | 9:ca11e4db63a7 | 66 | //queue.call_every(200, rosCom_thread); //Sets up sampling frequency of the velosity_thread |
ryanlin97 | 0:7e6b349182bc | 67 | t.reset(); |
jvfausto | 9:ca11e4db63a7 | 68 | compass.start(callback(&queue, &EventQueue::dispatch_forever)); //Starts running the compass thread |
jvfausto | 9:ca11e4db63a7 | 69 | velocity.start(callback(&queue, &EventQueue::dispatch_forever)); //Starts running the velosity thread |
jvfausto | 9:ca11e4db63a7 | 70 | assistSafe.start(callback(&queue, &EventQueue::dispatch_forever)); //Starts running the velosity thread |
jvfausto | 9:ca11e4db63a7 | 71 | //ros_com.start(callback(&queue, &EventQueue::dispatch_forever)); //Starts running the velosity thread |
JesiMiranda | 10:b5f6337c3a20 | 72 | pc.printf("After starting\r\n"); |
jvfausto | 9:ca11e4db63a7 | 73 | |
jvfausto | 9:ca11e4db63a7 | 74 | //added |
jvfausto | 9:ca11e4db63a7 | 75 | // int emerg_button = e_button; |
jvfausto | 9:ca11e4db63a7 | 76 | |
jvfausto | 9:ca11e4db63a7 | 77 | int set = 0; |
ryanlin97 | 0:7e6b349182bc | 78 | while(1) { |
ryanlin97 | 0:7e6b349182bc | 79 | if( pc.readable()) { |
jvfausto | 9:ca11e4db63a7 | 80 | set = 1; |
jvfausto | 9:ca11e4db63a7 | 81 | char c = pc.getc(); //Read the instruction sent |
ryanlin97 | 0:7e6b349182bc | 82 | if( c == 'w') { |
jvfausto | 9:ca11e4db63a7 | 83 | smart.forward(); //Move foward |
jvfausto | 9:ca11e4db63a7 | 84 | |
ryanlin97 | 0:7e6b349182bc | 85 | } |
ryanlin97 | 0:7e6b349182bc | 86 | else if( c == 'a') { |
jvfausto | 9:ca11e4db63a7 | 87 | smart.left(); //Turn left |
ryanlin97 | 0:7e6b349182bc | 88 | } |
jvfausto | 9:ca11e4db63a7 | 89 | else if( c == 'd') { |
jvfausto | 9:ca11e4db63a7 | 90 | smart.right(); //Turn right |
ryanlin97 | 0:7e6b349182bc | 91 | } |
jvfausto | 9:ca11e4db63a7 | 92 | else if( c == 's') { |
jvfausto | 9:ca11e4db63a7 | 93 | smart.backward(); //Turn rackwards |
jvfausto | 9:ca11e4db63a7 | 94 | } |
jvfausto | 9:ca11e4db63a7 | 95 | |
jvfausto | 9:ca11e4db63a7 | 96 | else if( c == 't') { |
jvfausto | 9:ca11e4db63a7 | 97 | smart.pid_twistA(); |
jvfausto | 9:ca11e4db63a7 | 98 | } else if(c == 'v'){ |
jvfausto | 9:ca11e4db63a7 | 99 | smart.showOdom(); |
jvfausto | 9:ca11e4db63a7 | 100 | } else if(c == 'o') { //Turns on chair |
jvfausto | 7:04f93e6b929f | 101 | pc.printf("turning on\r\n"); |
ryanlin97 | 6:e9b1684a9c00 | 102 | on = 1; |
ryanlin97 | 6:e9b1684a9c00 | 103 | wait(1); |
ryanlin97 | 6:e9b1684a9c00 | 104 | on = 0; |
jvfausto | 9:ca11e4db63a7 | 105 | } else if(c == 'f') { //Turns off chair |
jvfausto | 7:04f93e6b929f | 106 | pc.printf("turning off\r\n"); |
ryanlin97 | 6:e9b1684a9c00 | 107 | off = 1; |
ryanlin97 | 6:e9b1684a9c00 | 108 | wait(1); |
ryanlin97 | 6:e9b1684a9c00 | 109 | off = 0; |
jvfausto | 9:ca11e4db63a7 | 110 | |
jvfausto | 9:ca11e4db63a7 | 111 | } else if(c == 'k'){ //Sends command to go to the kitchen |
jvfausto | 9:ca11e4db63a7 | 112 | smart.pid_twistV(); |
jvfausto | 9:ca11e4db63a7 | 113 | } else if( c == 'm' || manual) { //Turns wheelchair to joystick |
jvfausto | 7:04f93e6b929f | 114 | pc.printf("turning on joystick\r\n"); |
ryanlin97 | 0:7e6b349182bc | 115 | manual = true; |
ryanlin97 | 0:7e6b349182bc | 116 | t.reset(); |
ryanlin97 | 0:7e6b349182bc | 117 | while(manual) { |
jvfausto | 9:ca11e4db63a7 | 118 | smart.move(x,y); //Reads from joystick and moves |
ryanlin97 | 0:7e6b349182bc | 119 | if( pc.readable()) { |
ryanlin97 | 0:7e6b349182bc | 120 | char d = pc.getc(); |
jvfausto | 9:ca11e4db63a7 | 121 | if( d == 'm') { //Turns wheelchair from joystick into auto |
jvfausto | 7:04f93e6b929f | 122 | pc.printf("turning off joystick\r\n"); |
ryanlin97 | 0:7e6b349182bc | 123 | manual = false; |
ryanlin97 | 0:7e6b349182bc | 124 | } |
ryanlin97 | 0:7e6b349182bc | 125 | } |
jvfausto | 7:04f93e6b929f | 126 | } |
ryanlin97 | 0:7e6b349182bc | 127 | } |
jvfausto | 9:ca11e4db63a7 | 128 | else { |
jvfausto | 9:ca11e4db63a7 | 129 | pc.printf("none \r\n"); |
jvfausto | 9:ca11e4db63a7 | 130 | smart.stop(); //If nothing else is happening stop the chair |
ryanlin97 | 0:7e6b349182bc | 131 | } |
ryanlin97 | 0:7e6b349182bc | 132 | } |
jvfausto | 9:ca11e4db63a7 | 133 | else { |
jvfausto | 9:ca11e4db63a7 | 134 | |
jvfausto | 9:ca11e4db63a7 | 135 | smart.stop(); //If nothing else is happening stop the chair |
jvfausto | 9:ca11e4db63a7 | 136 | } |
ryanlin97 | 0:7e6b349182bc | 137 | |
ryanlin97 | 0:7e6b349182bc | 138 | wait(process); |
ryanlin97 | 0:7e6b349182bc | 139 | } |
ryanlin97 | 0:7e6b349182bc | 140 | } |
ryanlin97 | 0:7e6b349182bc | 141 |