Updated with emergency button and watchdog code

Dependencies:   wheelchaircontrol4 Watchdog ros_lib_kinetic

Committer:
t1jain
Date:
Fri Jun 28 17:27:30 2019 +0000
Revision:
15:573dc6e9a1c6
Parent:
14:240bcc258bfe
Cleaned up code

Who changed what in which revision?

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