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