Summer 19 code

Dependencies:   wheelchaircontrol1

Committer:
jvfausto
Date:
Fri Jun 28 21:18:51 2019 +0000
Revision:
11:73b4380d82bf
Parent:
10:b4d68db3ddbd
a

Who changed what in which revision?

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