Updated with emergency button and watchdog code

Dependencies:   wheelchaircontrol4 Watchdog ros_lib_kinetic

Committer:
t1jain
Date:
Thu Jun 27 18:33:05 2019 +0000
Revision:
13:1d0ed92043af
Parent:
11:c9afd96fa08b
Child:
14:240bcc258bfe
Bug fixes

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