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