Summer 19 code

Dependencies:   wheelchaircontrol

Committer:
t1jain
Date:
Tue Jul 02 17:49:41 2019 +0000
Revision:
18:94ae9ca5a709
Parent:
17:770a161346ed
Cloned as Version 1.0

Who changed what in which revision?

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