changed pins for e_button and added code for turning off PCB

Dependencies:   wheelchairControlSummer2019 Watchdog ros_lib_kinetic

Committer:
JesiMiranda
Date:
Fri Jun 28 19:42:02 2019 +0000
Revision:
14:88e5a437a58a
Parent:
13:1d0ed92043af
changed pins for e_button and added code for turning off PCB

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