Back ToF code added (incomplete)
Dependencies: wheelchaircontrol1-6
main.cpp@19:7ead04523f89, 2019-07-02 (annotated)
- Committer:
- t1jain
- Date:
- Tue Jul 02 17:53:42 2019 +0000
- Revision:
- 19:7ead04523f89
- Parent:
- 18:94ae9ca5a709
- Child:
- 20:bd257ffdef24
Collated code for down ToF, side ToF, emergency button, Watchdog
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
t1jain | 19:7ead04523f89 | 1 | /************************** |
t1jain | 19:7ead04523f89 | 2 | * Version 1.0 * |
t1jain | 19:7ead04523f89 | 3 | **************************/ |
t1jain | 19:7ead04523f89 | 4 | |
ryanlin97 | 0:7e6b349182bc | 5 | #include "wheelchair.h" |
ryanlin97 | 0:7e6b349182bc | 6 | |
t1jain | 17:770a161346ed | 7 | QEI wheel (D10, D9, NC, 1200); // Initializes right encoder |
t1jain | 17:770a161346ed | 8 | DigitalIn pt3(D10, PullUp); // Pull up resistors to read analog signals into digital signals |
jvfausto | 9:ca11e4db63a7 | 9 | DigitalIn pt4(D9, PullUp); |
jvfausto | 9:ca11e4db63a7 | 10 | |
t1jain | 18:94ae9ca5a709 | 11 | DigitalIn e_button(D6, PullDown); // Change to PullUp if testing without Emergency Button Connected |
jvfausto | 8:db780b392bae | 12 | |
t1jain | 17:770a161346ed | 13 | QEI wheelS (D7, D8, NC, 1200); // Initializes Left encoder |
t1jain | 17:770a161346ed | 14 | DigitalIn pt1(D7, PullUp); // Pull up resistors to read analog signals into digital signals |
jvfausto | 9:ca11e4db63a7 | 15 | DigitalIn pt2(D8, PullUp); |
jvfausto | 8:db780b392bae | 16 | |
jvfausto | 9:ca11e4db63a7 | 17 | int max_velocity; |
jvfausto | 9:ca11e4db63a7 | 18 | |
t1jain | 17:770a161346ed | 19 | AnalogIn x(A0); // Initializes analog axis for the joystick |
ryanlin97 | 0:7e6b349182bc | 20 | AnalogIn y(A1); |
ryanlin97 | 0:7e6b349182bc | 21 | |
t1jain | 18:94ae9ca5a709 | 22 | |
t1jain | 17:770a161346ed | 23 | //Watchdog limit should be 0.1; Set to 1 for Testing Only |
t1jain | 17:770a161346ed | 24 | double watchdogLimit = 1; // Set timeout limit for watchdog timer in seconds |
jvfausto | 11:73b4380d82bf | 25 | int buttonCheck = 0; |
jvfausto | 11:73b4380d82bf | 26 | int iteration = 1; |
jvfausto | 11:73b4380d82bf | 27 | |
t1jain | 17:770a161346ed | 28 | DigitalOut up(D12); // Turn up speed mode for joystick |
t1jain | 17:770a161346ed | 29 | DigitalOut down(D13); // Turn down speed mode for joystick |
t1jain | 18:94ae9ca5a709 | 30 | |
t1jain | 18:94ae9ca5a709 | 31 | PwmOut on(PE_6); // Turn Wheelchair On |
t1jain | 18:94ae9ca5a709 | 32 | PwmOut off(PE_5); // Turn Wheelchair Off |
t1jain | 18:94ae9ca5a709 | 33 | |
t1jain | 17:770a161346ed | 34 | bool manual = false; // Turns chair joystic to automatic and viceverza |
jvfausto | 9:ca11e4db63a7 | 35 | |
t1jain | 17:770a161346ed | 36 | Serial pc(USBTX, USBRX, 57600); // Serial Monitor |
ryanlin97 | 0:7e6b349182bc | 37 | |
t1jain | 17:770a161346ed | 38 | VL53L1X sensor1(PD_13, PD_12, PC_7); // Initializes ToF sensors |
jvfausto | 11:73b4380d82bf | 39 | VL53L1X sensor2(PD_13, PD_12, PA_15); |
jvfausto | 10:b4d68db3ddbd | 40 | VL53L1X sensor3(PD_13, PD_12, PB_5); |
jvfausto | 11:73b4380d82bf | 41 | VL53L1X sensor4(PD_13, PD_12, PF_14); |
jvfausto | 11:73b4380d82bf | 42 | VL53L1X sensor5(PD_13, PD_12, PE_11); |
jvfausto | 10:b4d68db3ddbd | 43 | VL53L1X sensor6(PD_13, PD_12, PE_13); |
jvfausto | 10:b4d68db3ddbd | 44 | VL53L1X sensor7(PD_13, PD_12, D6); |
jvfausto | 10:b4d68db3ddbd | 45 | VL53L1X sensor8(PD_13, PD_12, PE_12); |
jvfausto | 10:b4d68db3ddbd | 46 | VL53L1X sensor9(PD_13, PD_12, PE_10); |
jvfausto | 10:b4d68db3ddbd | 47 | VL53L1X sensor10(PD_13, PD_12, PE_15); |
jvfausto | 10:b4d68db3ddbd | 48 | VL53L1X sensor11(PD_13, PD_12, D6); |
jvfausto | 9:ca11e4db63a7 | 49 | VL53L1X sensor12(PB_11, PB_10, D11); |
ryanlin97 | 5:90bf5f0d86e9 | 50 | |
jvfausto | 9:ca11e4db63a7 | 51 | VL53L1X* ToF[12] = {&sensor1, &sensor2, &sensor3, &sensor4, &sensor5, &sensor6, |
t1jain | 17:770a161346ed | 52 | &sensor7, &sensor8, &sensor9, &sensor10, &sensor11, &sensor12}; // Puts ToF sensor pointers into an array |
jvfausto | 9:ca11e4db63a7 | 53 | VL53L1X** ToFT = ToF; |
ryanlin97 | 0:7e6b349182bc | 54 | |
t1jain | 17:770a161346ed | 55 | Timer t; // Initialize time object t |
t1jain | 17:770a161346ed | 56 | EventQueue queue; // Class to organize threads |
t1jain | 17:770a161346ed | 57 | Wheelchair smart(xDir,yDir, &pc, &t, &wheel, &wheelS, ToFT); // Initialize wheelchair object |
t1jain | 17:770a161346ed | 58 | Thread compass; // Thread for compass |
t1jain | 17:770a161346ed | 59 | Thread velocity; // Thread for velosity |
t1jain | 17:770a161346ed | 60 | Thread ToFSafe; // Thread for safety stuff |
t1jain | 18:94ae9ca5a709 | 61 | Thread emergencyButton; // Thread to check button state and reset device |
ryanlin97 | 0:7e6b349182bc | 62 | |
ryanlin97 | 5:90bf5f0d86e9 | 63 | |
ryanlin97 | 0:7e6b349182bc | 64 | int main(void) |
jvfausto | 9:ca11e4db63a7 | 65 | { |
jvfausto | 9:ca11e4db63a7 | 66 | /* nh.initNode(); |
jvfausto | 9:ca11e4db63a7 | 67 | nh.advertise(chatter); |
jvfausto | 9:ca11e4db63a7 | 68 | nh.advertise(chatter2); |
jvfausto | 9:ca11e4db63a7 | 69 | nh.subscribe(sub);*/ |
t1jain | 17:770a161346ed | 70 | |
jvfausto | 9:ca11e4db63a7 | 71 | pc.printf("before starting\r\n"); |
t1jain | 18:94ae9ca5a709 | 72 | //queue.call_every(SAMPLEFREQ, &smart, &Wheelchair::compass_thread); // Sets up sampling frequency of the compass thread |
t1jain | 18:94ae9ca5a709 | 73 | queue.call_every(SAMPLEFREQ, &smart, &Wheelchair::velocity_thread); // Sets up sampling frequency of the velocity thread |
t1jain | 18:94ae9ca5a709 | 74 | queue.call_every(SAMPLEFREQ, &smart, &Wheelchair::ToFSafe_thread); // Sets up sampling frequency of the ToF safety thread |
t1jain | 18:94ae9ca5a709 | 75 | //queue.call_every(200, rosCom_thread); // Sets up sampling frequency of the ROS com thread |
t1jain | 18:94ae9ca5a709 | 76 | queue.call_every(SAMPLEFREQ, &smart, &Wheelchair::emergencyButton_thread); // Sets up sampling frequency of the emergency button thread |
t1jain | 18:94ae9ca5a709 | 77 | |
ryanlin97 | 0:7e6b349182bc | 78 | t.reset(); |
t1jain | 18:94ae9ca5a709 | 79 | //compass.start(callback(&queue, &EventQueue::dispatch_forever)); // Starts running the compass thread |
t1jain | 18:94ae9ca5a709 | 80 | velocity.start(callback(&queue, &EventQueue::dispatch_forever)); // Starts running the velocity thread |
t1jain | 18:94ae9ca5a709 | 81 | ToFSafe.start(callback(&queue, &EventQueue::dispatch_forever)); // Starts running the ROS com thread |
t1jain | 18:94ae9ca5a709 | 82 | //ros_com.start(callback(&queue, &EventQueue::dispatch_forever)); // Starts running the ROS com thread |
t1jain | 18:94ae9ca5a709 | 83 | emergencyButton.start(callback(&queue, &EventQueue::dispatch_forever)); // Starts running the emergency button thread |
t1jain | 18:94ae9ca5a709 | 84 | |
jvfausto | 9:ca11e4db63a7 | 85 | pc.printf("After starting\r\n"); |
jvfausto | 9:ca11e4db63a7 | 86 | |
jvfausto | 9:ca11e4db63a7 | 87 | //added |
jvfausto | 9:ca11e4db63a7 | 88 | // int emerg_button = e_button; |
jvfausto | 13:7fe71170d157 | 89 | Watchdog dog; // Creates Watchdog object |
jvfausto | 13:7fe71170d157 | 90 | dog.Configure(watchdogLimit); // Configures timeout for Watchdog |
jvfausto | 13:7fe71170d157 | 91 | pc.printf("Code initiated\n"); |
jvfausto | 9:ca11e4db63a7 | 92 | int set = 0; |
ryanlin97 | 0:7e6b349182bc | 93 | while(1) { |
ryanlin97 | 0:7e6b349182bc | 94 | if( pc.readable()) { |
jvfausto | 9:ca11e4db63a7 | 95 | set = 1; |
t1jain | 17:770a161346ed | 96 | char c = pc.getc(); // Read the instruction sent |
ryanlin97 | 0:7e6b349182bc | 97 | if( c == 'w') { |
t1jain | 17:770a161346ed | 98 | smart.forward(); // Move foward |
jvfausto | 9:ca11e4db63a7 | 99 | |
ryanlin97 | 0:7e6b349182bc | 100 | } |
ryanlin97 | 0:7e6b349182bc | 101 | else if( c == 'a') { |
t1jain | 17:770a161346ed | 102 | smart.left(); // Turn left |
ryanlin97 | 0:7e6b349182bc | 103 | } |
jvfausto | 9:ca11e4db63a7 | 104 | else if( c == 'd') { |
t1jain | 17:770a161346ed | 105 | smart.right(); // Turn right |
ryanlin97 | 0:7e6b349182bc | 106 | } |
jvfausto | 9:ca11e4db63a7 | 107 | else if( c == 's') { |
t1jain | 17:770a161346ed | 108 | smart.backward(); // Turn backwards |
jvfausto | 9:ca11e4db63a7 | 109 | } |
jvfausto | 9:ca11e4db63a7 | 110 | |
jvfausto | 9:ca11e4db63a7 | 111 | else if( c == 't') { |
jvfausto | 9:ca11e4db63a7 | 112 | smart.pid_twistA(); |
jvfausto | 9:ca11e4db63a7 | 113 | } else if(c == 'v'){ |
jvfausto | 9:ca11e4db63a7 | 114 | smart.showOdom(); |
t1jain | 17:770a161346ed | 115 | } else if(c == 'o') { // Turns on chair |
jvfausto | 7:04f93e6b929f | 116 | pc.printf("turning on\r\n"); |
ryanlin97 | 6:e9b1684a9c00 | 117 | on = 1; |
ryanlin97 | 6:e9b1684a9c00 | 118 | wait(1); |
ryanlin97 | 6:e9b1684a9c00 | 119 | on = 0; |
t1jain | 17:770a161346ed | 120 | } else if(c == 'f') { // Turns off chair |
jvfausto | 7:04f93e6b929f | 121 | pc.printf("turning off\r\n"); |
ryanlin97 | 6:e9b1684a9c00 | 122 | off = 1; |
ryanlin97 | 6:e9b1684a9c00 | 123 | wait(1); |
ryanlin97 | 6:e9b1684a9c00 | 124 | off = 0; |
jvfausto | 9:ca11e4db63a7 | 125 | |
t1jain | 17:770a161346ed | 126 | } else if(c == 'k'){ // Sends command to go to the kitchen |
jvfausto | 9:ca11e4db63a7 | 127 | smart.pid_twistV(); |
t1jain | 17:770a161346ed | 128 | } else if( c == 'm' || manual) { // Turns wheelchair to joystick |
jvfausto | 7:04f93e6b929f | 129 | pc.printf("turning on joystick\r\n"); |
ryanlin97 | 0:7e6b349182bc | 130 | manual = true; |
ryanlin97 | 0:7e6b349182bc | 131 | t.reset(); |
ryanlin97 | 0:7e6b349182bc | 132 | while(manual) { |
t1jain | 17:770a161346ed | 133 | smart.move(x,y); // Reads from joystick and moves |
ryanlin97 | 0:7e6b349182bc | 134 | if( pc.readable()) { |
ryanlin97 | 0:7e6b349182bc | 135 | char d = pc.getc(); |
t1jain | 17:770a161346ed | 136 | if( d == 'm') { // Turns wheelchair from joystick into auto |
jvfausto | 7:04f93e6b929f | 137 | pc.printf("turning off joystick\r\n"); |
ryanlin97 | 0:7e6b349182bc | 138 | manual = false; |
ryanlin97 | 0:7e6b349182bc | 139 | } |
ryanlin97 | 0:7e6b349182bc | 140 | } |
jvfausto | 7:04f93e6b929f | 141 | } |
ryanlin97 | 0:7e6b349182bc | 142 | } |
jvfausto | 9:ca11e4db63a7 | 143 | else { |
jvfausto | 9:ca11e4db63a7 | 144 | pc.printf("none \r\n"); |
t1jain | 17:770a161346ed | 145 | smart.stop(); // If nothing else is happening stop the chair |
ryanlin97 | 0:7e6b349182bc | 146 | } |
ryanlin97 | 0:7e6b349182bc | 147 | } |
jvfausto | 9:ca11e4db63a7 | 148 | else { |
jvfausto | 9:ca11e4db63a7 | 149 | |
t1jain | 17:770a161346ed | 150 | smart.stop(); // If nothing else is happening stop the chair |
jvfausto | 9:ca11e4db63a7 | 151 | } |
jvfausto | 11:73b4380d82bf | 152 | |
ryanlin97 | 0:7e6b349182bc | 153 | wait(process); |
jvfausto | 11:73b4380d82bf | 154 | |
jvfausto | 13:7fe71170d157 | 155 | t.stop(); |
t1jain | 14:67133c127740 | 156 | //pc.printf("Time elapsed: %f seconds and iteration = %d\n", t.read(), iteration); |
t1jain | 17:770a161346ed | 157 | dog.Service(); // Service the Watchdog so it does not cause a system reset - "Kicking"/"Feeding" the dog |
jvfausto | 13:7fe71170d157 | 158 | |
ryanlin97 | 0:7e6b349182bc | 159 | } |
ryanlin97 | 0:7e6b349182bc | 160 | } |
ryanlin97 | 0:7e6b349182bc | 161 |