Where we will test the side ToF sensors

Dependencies:   QEI2 PID Watchdog VL53L1X_Filter ros_lib_kinetic

Committer:
isagmz
Date:
Tue Jul 09 17:52:32 2019 +0000
Revision:
21:d1faccb96146
Parent:
17:770a161346ed
Finished IMU side sensor code

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
jvfausto 9:ca11e4db63a7 7 /*added*/
t1jain 17:770a161346ed 8 //DigitalIn e_button(D4); // Emergency button will start at HIGH
jvfausto 8:db780b392bae 9
t1jain 17:770a161346ed 10 QEI wheelS (D7, D8, NC, 1200); // Initializes Left encoder
t1jain 17:770a161346ed 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
t1jain 17:770a161346ed 17 AnalogIn x(A0); // Initializes analog axis for the joystick
ryanlin97 0:7e6b349182bc 18 AnalogIn y(A1);
ryanlin97 0:7e6b349182bc 19
t1jain 17:770a161346ed 20 //Watchdog limit should be 0.1; Set to 1 for Testing Only
t1jain 17:770a161346ed 21 double watchdogLimit = 1; // Set timeout limit for watchdog timer in seconds
jvfausto 11:73b4380d82bf 22 int buttonCheck = 0;
jvfausto 11:73b4380d82bf 23 int iteration = 1;
jvfausto 11:73b4380d82bf 24
t1jain 17:770a161346ed 25 DigitalOut up(D12); // Turn up speed mode for joystick
t1jain 17:770a161346ed 26 DigitalOut down(D13); // Turn down speed mode for joystick
t1jain 17:770a161346ed 27 DigitalOut on(D14); // Turn Wheelchair On
t1jain 17:770a161346ed 28 DigitalOut off(D15); // Turn Wheelchair Off
t1jain 17:770a161346ed 29 bool manual = false; // Turns chair joystic to automatic and viceverza
jvfausto 9:ca11e4db63a7 30
t1jain 17:770a161346ed 31 Serial pc(USBTX, USBRX, 57600); // Serial Monitor
ryanlin97 0:7e6b349182bc 32
t1jain 17:770a161346ed 33 VL53L1X sensor1(PD_13, PD_12, PC_7); // Initializes ToF sensors
jvfausto 11:73b4380d82bf 34 VL53L1X sensor2(PD_13, PD_12, PA_15);
jvfausto 10:b4d68db3ddbd 35 VL53L1X sensor3(PD_13, PD_12, PB_5);
jvfausto 11:73b4380d82bf 36 VL53L1X sensor4(PD_13, PD_12, PF_14);
jvfausto 11:73b4380d82bf 37 VL53L1X sensor5(PD_13, PD_12, PE_11);
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 17:770a161346ed 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
isagmz 21:d1faccb96146 50 Timer imuTimer;
isagmz 21:d1faccb96146 51 IMUWheelchair IMU(&pc,&imuTimer); //initialize IMU
isagmz 21:d1faccb96146 52
t1jain 17:770a161346ed 53 Timer t; // Initialize time object t
t1jain 17:770a161346ed 54 EventQueue queue; // Class to organize threads
isagmz 21:d1faccb96146 55 Wheelchair smart(xDir,yDir, &pc, &t, &imuTimer, &wheel, &wheelS, ToFT); // Initialize wheelchair object
t1jain 17:770a161346ed 56 Thread compass; // Thread for compass
t1jain 17:770a161346ed 57 Thread velocity; // Thread for velosity
t1jain 17:770a161346ed 58 Thread ToFSafe; // Thread for safety stuff
ryanlin97 0:7e6b349182bc 59
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();
t1jain 17:770a161346ed 68
jvfausto 9:ca11e4db63a7 69 pc.printf("before starting\r\n");
t1jain 17:770a161346ed 70 //queue.call_every(SAMPLEFREQ, &smart, &Wheelchair::compass_thread); // Sets up sampling frequency of the compass_thread
t1jain 17:770a161346ed 71 queue.call_every(SAMPLEFREQ, &smart, &Wheelchair::velocity_thread); // Sets up sampling frequency of the velosity_thread
t1jain 17:770a161346ed 72 queue.call_every(SAMPLEFREQ, &smart, &Wheelchair::ToFSafe_thread); // Sets up sampling frequency of the velosity_thread
t1jain 17:770a161346ed 73 //queue.call_every(200, rosCom_thread); // Sets up sampling frequency of the velosity_thread
ryanlin97 0:7e6b349182bc 74 t.reset();
t1jain 17:770a161346ed 75 //compass.start(callback(&queue, &EventQueue::dispatch_forever)); // Starts running the compass thread
t1jain 17:770a161346ed 76 velocity.start(callback(&queue, &EventQueue::dispatch_forever)); // Starts running the velosity thread
t1jain 17:770a161346ed 77 ToFSafe.start(callback(&queue, &EventQueue::dispatch_forever)); // Starts running the velosity thread
t1jain 17:770a161346ed 78 //ros_com.start(callback(&queue, &EventQueue::dispatch_forever)); // Starts running the velosity thread
jvfausto 9:ca11e4db63a7 79 pc.printf("After starting\r\n");
jvfausto 9:ca11e4db63a7 80
jvfausto 9:ca11e4db63a7 81 //added
jvfausto 9:ca11e4db63a7 82 // int emerg_button = e_button;
jvfausto 13:7fe71170d157 83 Watchdog dog; // Creates Watchdog object
jvfausto 13:7fe71170d157 84 dog.Configure(watchdogLimit); // Configures timeout for Watchdog
jvfausto 13:7fe71170d157 85 pc.printf("Code initiated\n");
jvfausto 9:ca11e4db63a7 86 int set = 0;
ryanlin97 0:7e6b349182bc 87 while(1) {
ryanlin97 0:7e6b349182bc 88 if( pc.readable()) {
jvfausto 9:ca11e4db63a7 89 set = 1;
t1jain 17:770a161346ed 90 char c = pc.getc(); // Read the instruction sent
ryanlin97 0:7e6b349182bc 91 if( c == 'w') {
t1jain 17:770a161346ed 92 smart.forward(); // Move foward
jvfausto 9:ca11e4db63a7 93
ryanlin97 0:7e6b349182bc 94 }
ryanlin97 0:7e6b349182bc 95 else if( c == 'a') {
t1jain 17:770a161346ed 96 smart.left(); // Turn left
ryanlin97 0:7e6b349182bc 97 }
jvfausto 9:ca11e4db63a7 98 else if( c == 'd') {
t1jain 17:770a161346ed 99 smart.right(); // Turn right
ryanlin97 0:7e6b349182bc 100 }
jvfausto 9:ca11e4db63a7 101 else if( c == 's') {
t1jain 17:770a161346ed 102 smart.backward(); // Turn backwards
jvfausto 9:ca11e4db63a7 103 }
jvfausto 9:ca11e4db63a7 104
jvfausto 9:ca11e4db63a7 105 else if( c == 't') {
jvfausto 9:ca11e4db63a7 106 smart.pid_twistA();
jvfausto 9:ca11e4db63a7 107 } else if(c == 'v'){
jvfausto 9:ca11e4db63a7 108 smart.showOdom();
t1jain 17:770a161346ed 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;
t1jain 17:770a161346ed 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;
jvfausto 9:ca11e4db63a7 119
t1jain 17:770a161346ed 120 } else if(c == 'k'){ // Sends command to go to the kitchen
jvfausto 9:ca11e4db63a7 121 smart.pid_twistV();
t1jain 17:770a161346ed 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) {
t1jain 17:770a161346ed 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();
t1jain 17:770a161346ed 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 }
jvfausto 7:04f93e6b929f 135 }
ryanlin97 0:7e6b349182bc 136 }
jvfausto 9:ca11e4db63a7 137 else {
jvfausto 9:ca11e4db63a7 138 pc.printf("none \r\n");
t1jain 17:770a161346ed 139 smart.stop(); // If nothing else is happening stop the chair
ryanlin97 0:7e6b349182bc 140 }
ryanlin97 0:7e6b349182bc 141 }
jvfausto 9:ca11e4db63a7 142 else {
jvfausto 9:ca11e4db63a7 143
t1jain 17:770a161346ed 144 smart.stop(); // If nothing else is happening stop the chair
jvfausto 9:ca11e4db63a7 145 }
jvfausto 11:73b4380d82bf 146
ryanlin97 0:7e6b349182bc 147 wait(process);
jvfausto 11:73b4380d82bf 148
jvfausto 13:7fe71170d157 149 t.stop();
t1jain 14:67133c127740 150 //pc.printf("Time elapsed: %f seconds and iteration = %d\n", t.read(), iteration);
t1jain 17:770a161346ed 151 dog.Service(); // Service the Watchdog so it does not cause a system reset - "Kicking"/"Feeding" the dog
jvfausto 13:7fe71170d157 152
ryanlin97 0:7e6b349182bc 153 }
ryanlin97 0:7e6b349182bc 154 }
ryanlin97 0:7e6b349182bc 155