Added more code for side and angled sensor

Dependencies:   QEI2 PID Watchdog VL53L1X_Filter BNOWrapper ros_lib_kinetic

Committer:
t1jain
Date:
Thu Jul 11 18:38:03 2019 +0000
Revision:
40:11b8567c507b
Parent:
39:5438557a8b4e
Child:
41:1a687bcf4b0a
Back ToF added

Who changed what in which revision?

UserRevisionLine numberNew contents of line
JesiMiranda 35:5a2fed4c2e9f 1 /*************************************************************************
JesiMiranda 35:5a2fed4c2e9f 2 * Importing header into wheelchair.cpp *
JesiMiranda 35:5a2fed4c2e9f 3 **************************************************************************/
ryanlin97 0:fc0c4a184482 4 #include "wheelchair.h"
t1jain 30:c25b2556e84d 5
JesiMiranda 35:5a2fed4c2e9f 6 /*************************************************************************
JesiMiranda 35:5a2fed4c2e9f 7 * Defining global variables *
JesiMiranda 35:5a2fed4c2e9f 8 **************************************************************************/
jvfausto 21:3489cffad196 9 bool manual_drive = false; // Variable changes between joystick and auto drive
jvfausto 21:3489cffad196 10 double encoder_distance; // Keeps distanse due to original position
JesiMiranda 35:5a2fed4c2e9f 11
jvfausto 21:3489cffad196 12 volatile double Setpoint, Output, Input, Input2; // Variables for PID
jvfausto 21:3489cffad196 13 volatile double pid_yaw, Distance, Setpoint2, Output2, encoder_distance2; // Variables for PID
jvfausto 21:3489cffad196 14 volatile double vIn, vOut, vDesired; // Variables for PID Velosity
jvfausto 21:3489cffad196 15 volatile double vInS, vOutS, vDesiredS; // Variables for PID Slave Wheel
jvfausto 21:3489cffad196 16 volatile double yIn, yOut, yDesired; // Variables for PID turn velosity
t1jain 30:c25b2556e84d 17 // int* ToFDataPointer1;
t1jain 30:c25b2556e84d 18 // int* ToFDataPointer2;
t1jain 30:c25b2556e84d 19
JesiMiranda 35:5a2fed4c2e9f 20 int ledgeArrayLF[150];
JesiMiranda 35:5a2fed4c2e9f 21 int ledgeArrayRF[150];
t1jain 30:c25b2556e84d 22 int* ToFDataPointer1 = ledgeArrayLF;
t1jain 30:c25b2556e84d 23 int* ToFDataPointer2 = ledgeArrayRF;
JesiMiranda 35:5a2fed4c2e9f 24 Statistics LFTStats(ToFDataPointer1, 149, 1);
JesiMiranda 35:5a2fed4c2e9f 25 Statistics RFTStats(ToFDataPointer2, 149, 1);
t1jain 40:11b8567c507b 26 int k = 0;
t1jain 38:cb87f4e353b9 27
t1jain 38:cb87f4e353b9 28 int ledgeArrayLB[150];
t1jain 38:cb87f4e353b9 29 int ledgeArrayRB[150];
t1jain 38:cb87f4e353b9 30 int* ToFDataPointer3 = ledgeArrayLB;
t1jain 38:cb87f4e353b9 31 int* ToFDataPointer4 = ledgeArrayRB;
t1jain 38:cb87f4e353b9 32 Statistics LBTStats(ToFDataPointer3, 149, 1);
t1jain 38:cb87f4e353b9 33 Statistics RBTStats(ToFDataPointer4, 149, 1);
ryanlin97 11:d14a1f7f1297 34
jvfausto 21:3489cffad196 35 double dist_old, curr_pos; // Variables for odometry position
t1jain 30:c25b2556e84d 36 double outlierToF[4];
jvfausto 19:71a6621ee5c3 37
JesiMiranda 35:5a2fed4c2e9f 38 /*************************************************************************
JesiMiranda 35:5a2fed4c2e9f 39 * Creating PID objects *
JesiMiranda 35:5a2fed4c2e9f 40 **************************************************************************/
jvfausto 21:3489cffad196 41 PID myPID(&pid_yaw, &Output, &Setpoint, 5.5, .00, 0.0036, P_ON_E, DIRECT); // Angle PID object constructor
jvfausto 21:3489cffad196 42 PID myPIDDistance(&Input, &Output, &Setpoint, 5.5, .00, 0.002, P_ON_E, DIRECT); // Distance PID object constructor
jvfausto 21:3489cffad196 43 PID PIDVelosity(&vIn, &vOut, &vDesired, 5.5, .00, .002, P_ON_E, DIRECT); // Velosity PID Constructor
jvfausto 21:3489cffad196 44 PID PIDSlaveV(&vInS, &vOutS, &vDesiredS, 5.5, .00, .002, P_ON_E, DIRECT); // Slave Velosity PID Constructor
jvfausto 21:3489cffad196 45 PID PIDAngularV(&yIn, &yOut, &yDesired, 5.5, .00, .002, P_ON_E, DIRECT); // Angular Velosity PID Constructor
JesiMiranda 35:5a2fed4c2e9f 46
jvfausto 19:71a6621ee5c3 47
JesiMiranda 35:5a2fed4c2e9f 48 /*************************************************************************
JesiMiranda 35:5a2fed4c2e9f 49 * Thread measures current angular position *
JesiMiranda 35:5a2fed4c2e9f 50 **************************************************************************/
JesiMiranda 35:5a2fed4c2e9f 51 void Wheelchair::compass_thread()
JesiMiranda 35:5a2fed4c2e9f 52 {
JesiMiranda 35:5a2fed4c2e9f 53 curr_yaw = imu->yaw();
JesiMiranda 35:5a2fed4c2e9f 54 z_angular = curr_yaw;
jvfausto 21:3489cffad196 55 }
jvfausto 17:7f3b69300bb6 56
JesiMiranda 35:5a2fed4c2e9f 57 /*************************************************************************
JesiMiranda 35:5a2fed4c2e9f 58 * Thread measures velocity of wheels and distance traveled *
JesiMiranda 35:5a2fed4c2e9f 59 **************************************************************************/
JesiMiranda 35:5a2fed4c2e9f 60 void Wheelchair::velocity_thread()
ryanlin97 1:c0beadca1617 61 {
jvfausto 21:3489cffad196 62 curr_vel = wheel->getVelocity();
jvfausto 21:3489cffad196 63 curr_velS = wheelS->getVelocity();
jvfausto 21:3489cffad196 64 curr_pos = wheel->getDistance(53.975);
ryanlin97 1:c0beadca1617 65 }
ryanlin97 6:0cd57bdd8fbc 66
t1jain 34:b89967adc86c 67 void Wheelchair::emergencyButton_thread ()
t1jain 34:b89967adc86c 68 {
t1jain 34:b89967adc86c 69 while(1) {
t1jain 34:b89967adc86c 70 while(!e_button) {
t1jain 34:b89967adc86c 71
t1jain 34:b89967adc86c 72 //Stop wheelchair
t1jain 34:b89967adc86c 73 Wheelchair::stop();
t1jain 34:b89967adc86c 74 printf("E-button has been pressed\r\n");
t1jain 34:b89967adc86c 75 off->write(high); // Turn off PCB
t1jain 34:b89967adc86c 76 on->write(0); // Make sure PCB not on
t1jain 34:b89967adc86c 77 //Reset Board
t1jain 34:b89967adc86c 78 NVIC_SystemReset();
t1jain 34:b89967adc86c 79
t1jain 34:b89967adc86c 80 }
t1jain 34:b89967adc86c 81
t1jain 34:b89967adc86c 82 }
t1jain 34:b89967adc86c 83 }
t1jain 34:b89967adc86c 84
JesiMiranda 35:5a2fed4c2e9f 85 /*************************************************************************
JesiMiranda 37:e0e6d3fe06a2 86 * Thread checks ToF sensors for safety of wheelchair movement *
JesiMiranda 35:5a2fed4c2e9f 87 **************************************************************************/
t1jain 30:c25b2556e84d 88 void Wheelchair::ToFSafe_thread()
ryanlin97 1:c0beadca1617 89 {
jvfausto 21:3489cffad196 90 int ToFV[12];
JesiMiranda 35:5a2fed4c2e9f 91 for(int i = 0; i < 6; i++) { // Reads from the ToF Sensors
jvfausto 21:3489cffad196 92 ToFV[i] = (*(ToF+i))->readFromOneSensor();
t1jain 32:fb26baa75d44 93 //out->printf("%d ", ToFV[i]);
JesiMiranda 35:5a2fed4c2e9f 94 }
JesiMiranda 35:5a2fed4c2e9f 95
JesiMiranda 35:5a2fed4c2e9f 96 //out->printf("\r\n");
JesiMiranda 35:5a2fed4c2e9f 97
t1jain 40:11b8567c507b 98 k++;
JesiMiranda 35:5a2fed4c2e9f 99
t1jain 40:11b8567c507b 100 if (k == 150) {
t1jain 40:11b8567c507b 101 k = 1;
t1jain 30:c25b2556e84d 102 }
JesiMiranda 35:5a2fed4c2e9f 103
t1jain 40:11b8567c507b 104 ledgeArrayLF[k] = (*(ToF+1))->readFromOneSensor();
t1jain 40:11b8567c507b 105 ledgeArrayRF[k] = (*(ToF+4))->readFromOneSensor();
JesiMiranda 35:5a2fed4c2e9f 106
t1jain 31:06f2362caf12 107 /*for(int i = 0; i < 100; i++)
t1jain 31:06f2362caf12 108 {
t1jain 31:06f2362caf12 109 out->printf("%d, ",ledgeArrayRF[i]);
t1jain 31:06f2362caf12 110 }
t1jain 31:06f2362caf12 111 out->printf("\r\n");*/
t1jain 34:b89967adc86c 112
t1jain 30:c25b2556e84d 113 outlierToF[0] = LFTStats.mean() + 2*LFTStats.stdev();
JesiMiranda 35:5a2fed4c2e9f 114 outlierToF[1] = RFTStats.mean() + 2*RFTStats.stdev();
JesiMiranda 35:5a2fed4c2e9f 115
t1jain 40:11b8567c507b 116 for(int i = 0; i < 2; i++) { // Reads from the ToF Sensors
jvfausto 27:da718b990837 117 runningAverage[i] = ((runningAverage[i]*(4) + ToFV[(i*3)+1]) / 5);
t1jain 30:c25b2556e84d 118 }
JesiMiranda 35:5a2fed4c2e9f 119
jvfausto 27:da718b990837 120 int sensor1 = ToFV[0];
jvfausto 27:da718b990837 121 int sensor4 = ToFV[3];
JesiMiranda 35:5a2fed4c2e9f 122 if(curr_vel < 1 &&((2 * maxDecelerationSlow*sensor1 < curr_vel*curr_vel*1000*1000 ||
JesiMiranda 35:5a2fed4c2e9f 123 2 * maxDecelerationSlow*sensor4 < curr_vel*curr_vel*1000*1000) &&
JesiMiranda 35:5a2fed4c2e9f 124 (sensor1 < 1500 || sensor4 < 1500)) ||
JesiMiranda 35:5a2fed4c2e9f 125 550 > sensor1 || 550 > sensor4) {
JesiMiranda 35:5a2fed4c2e9f 126 if(x->read() > def) {
jvfausto 26:662693bd7f31 127 x->write(def);
t1jain 30:c25b2556e84d 128 forwardSafety = 1; // You cannot move forward
jvfausto 26:662693bd7f31 129 }
jvfausto 26:662693bd7f31 130 }
JesiMiranda 35:5a2fed4c2e9f 131
JesiMiranda 35:5a2fed4c2e9f 132 else if(curr_vel > 1 &&((2 * maxDecelerationFast*sensor1 < curr_vel*curr_vel*1000*1000 ||
JesiMiranda 35:5a2fed4c2e9f 133 2 * maxDecelerationFast*sensor4 < curr_vel*curr_vel*1000*1000) &&
JesiMiranda 35:5a2fed4c2e9f 134 (sensor1 < 1500 || sensor4 < 1500)) ||
JesiMiranda 35:5a2fed4c2e9f 135 550 > sensor1 || 550 > sensor4) {
JesiMiranda 35:5a2fed4c2e9f 136 if(x->read() > def) {
jvfausto 21:3489cffad196 137 x->write(def);
t1jain 34:b89967adc86c 138 forwardSafety = 1; // You cannot move forward
jvfausto 21:3489cffad196 139 }
jvfausto 21:3489cffad196 140 }
JesiMiranda 35:5a2fed4c2e9f 141
t1jain 30:c25b2556e84d 142 else if ((runningAverage[0] > outlierToF[0]) || (runningAverage[1] > outlierToF[1])) {
t1jain 30:c25b2556e84d 143 forwardSafety = 1;
t1jain 38:cb87f4e353b9 144 out->printf("I'M STOPPING BECAUSE OF A FRONT LEDGE\r\n");
JesiMiranda 35:5a2fed4c2e9f 145 }
JesiMiranda 35:5a2fed4c2e9f 146
jvfausto 21:3489cffad196 147 else
jvfausto 21:3489cffad196 148 forwardSafety = 0;
t1jain 38:cb87f4e353b9 149
t1jain 38:cb87f4e353b9 150 ////////////////////////////////////////////////////////////////////////////
t1jain 38:cb87f4e353b9 151
t1jain 40:11b8567c507b 152 // k2++;
t1jain 40:11b8567c507b 153 //
t1jain 40:11b8567c507b 154 // if (k2 == 150) {
t1jain 40:11b8567c507b 155 // k2 = 0;
t1jain 40:11b8567c507b 156 // }
t1jain 38:cb87f4e353b9 157
t1jain 40:11b8567c507b 158 ledgeArrayLB[k] = (*(ToF+1))->readFromOneSensor();
t1jain 40:11b8567c507b 159 ledgeArrayRB[k] = (*(ToF+4))->readFromOneSensor();
t1jain 38:cb87f4e353b9 160
t1jain 38:cb87f4e353b9 161 outlierToF[2] = LBTStats.mean() + 2*LBTStats.stdev();
t1jain 38:cb87f4e353b9 162 outlierToF[3] = RBTStats.mean() + 2*RBTStats.stdev();
t1jain 38:cb87f4e353b9 163
t1jain 40:11b8567c507b 164 for(int i = 2; i < 4; i++) { // Reads from the ToF Sensors
t1jain 38:cb87f4e353b9 165 runningAverage[i] = ((runningAverage[i]*(4) + ToFV[(i*3)+1]) / 5);
t1jain 38:cb87f4e353b9 166 }
t1jain 38:cb87f4e353b9 167
t1jain 38:cb87f4e353b9 168 int sensor7 = ToFV[6];
t1jain 38:cb87f4e353b9 169 int sensor10 = ToFV[9];
t1jain 38:cb87f4e353b9 170 if(curr_vel < 1 &&((2 * maxDecelerationSlow*sensor7 < curr_vel*curr_vel*1000*1000 ||
t1jain 38:cb87f4e353b9 171 2 * maxDecelerationSlow*sensor10 < curr_vel*curr_vel*1000*1000) &&
t1jain 38:cb87f4e353b9 172 (sensor7 < 1500 || sensor10 < 1500)) ||
t1jain 38:cb87f4e353b9 173 550 > sensor7 || 550 > sensor10) {
t1jain 38:cb87f4e353b9 174 if(x->read() > def) {
t1jain 38:cb87f4e353b9 175 x->write(def);
t1jain 39:5438557a8b4e 176 backwardSafety = 1; // You cannot move backwards
t1jain 38:cb87f4e353b9 177 }
t1jain 38:cb87f4e353b9 178 }
t1jain 38:cb87f4e353b9 179
t1jain 38:cb87f4e353b9 180 else if(curr_vel > 1 &&((2 * maxDecelerationFast*sensor1 < curr_vel*curr_vel*1000*1000 ||
t1jain 38:cb87f4e353b9 181 2 * maxDecelerationFast*sensor4 < curr_vel*curr_vel*1000*1000) &&
t1jain 38:cb87f4e353b9 182 (sensor7 < 1500 || sensor10 < 1500)) ||
t1jain 38:cb87f4e353b9 183 550 > sensor7 || 550 > sensor10) {
t1jain 38:cb87f4e353b9 184 if(x->read() > def) {
t1jain 38:cb87f4e353b9 185 x->write(def);
t1jain 39:5438557a8b4e 186 backwardSafety = 1; // You cannot move backwards
t1jain 38:cb87f4e353b9 187 }
t1jain 38:cb87f4e353b9 188 }
t1jain 38:cb87f4e353b9 189
t1jain 38:cb87f4e353b9 190 else if ((runningAverage[2] > outlierToF[2]) || (runningAverage[3] > outlierToF[3])) {
t1jain 38:cb87f4e353b9 191 backwardSafety = 1;
t1jain 38:cb87f4e353b9 192 out->printf("I'M STOPPING BECAUSE OF A BACK LEDGE\r\n");
t1jain 38:cb87f4e353b9 193 }
t1jain 38:cb87f4e353b9 194
t1jain 38:cb87f4e353b9 195 else
t1jain 38:cb87f4e353b9 196 backwardSafety = 0;
t1jain 38:cb87f4e353b9 197
t1jain 38:cb87f4e353b9 198
t1jain 38:cb87f4e353b9 199 ////////////////////////////////////////////////////////////////////////////
JesiMiranda 35:5a2fed4c2e9f 200
JesiMiranda 37:e0e6d3fe06a2 201 /*Side Tof begin*/
t1jain 34:b89967adc86c 202 int sensor3 = ToFV[2]; //front left
t1jain 34:b89967adc86c 203 int sensor6 = ToFV[5]; //front right
t1jain 34:b89967adc86c 204 int sensor9 = ToFV[8]; //back
t1jain 34:b89967adc86c 205 int sensor12 = ToFV[11]; //back
t1jain 34:b89967adc86c 206
JesiMiranda 37:e0e6d3fe06a2 207 double currAngularVelocity = imu->gyro_x(); //Current angular velocity from IMU
JesiMiranda 37:e0e6d3fe06a2 208 double angle = imu->yaw() * 3.14159 / 180; //from IMU, in rads
JesiMiranda 37:e0e6d3fe06a2 209 double arcLength = WheelchairRadius * currAngularVelocity *
JesiMiranda 37:e0e6d3fe06a2 210 currAngularVelocity / (2 * maxAngularDeceleration); //S = r*Ө, in cm
JesiMiranda 37:e0e6d3fe06a2 211
JesiMiranda 37:e0e6d3fe06a2 212 /* Clear the front side first, else continue going straight or can't turn
JesiMiranda 37:e0e6d3fe06a2 213 After clearing the front sideand movinf forward, check if can clear the back
JesiMiranda 37:e0e6d3fe06a2 214 when turning */
JesiMiranda 37:e0e6d3fe06a2 215
JesiMiranda 37:e0e6d3fe06a2 216 //When either sensors too close to the wall, can't turn
JesiMiranda 37:e0e6d3fe06a2 217 if(sensor3 <= minWallLength) {
JesiMiranda 37:e0e6d3fe06a2 218 leftSafety = 1;
JesiMiranda 37:e0e6d3fe06a2 219 out-> printf("Detecting wall to the left!\n");
JesiMiranda 37:e0e6d3fe06a2 220 }
JesiMiranda 37:e0e6d3fe06a2 221 else{
JesiMiranda 37:e0e6d3fe06a2 222 leftSafety = 0;
JesiMiranda 37:e0e6d3fe06a2 223 }
JesiMiranda 37:e0e6d3fe06a2 224
JesiMiranda 37:e0e6d3fe06a2 225 if(sensor6 <= minWallLength) {
JesiMiranda 37:e0e6d3fe06a2 226 rightSafety = 1;
JesiMiranda 37:e0e6d3fe06a2 227 out-> printf("Detecting wall to the right!\n");
JesiMiranda 37:e0e6d3fe06a2 228 }
JesiMiranda 37:e0e6d3fe06a2 229 else {
JesiMiranda 37:e0e6d3fe06a2 230 rightSafety = 0;
t1jain 34:b89967adc86c 231 }
t1jain 34:b89967adc86c 232
JesiMiranda 37:e0e6d3fe06a2 233 /*Check whether safe to keep turning
JesiMiranda 37:e0e6d3fe06a2 234 Know the exact moment you can stop the chair going at a certain speed before
JesiMiranda 37:e0e6d3fe06a2 235 its too late*/
JesiMiranda 37:e0e6d3fe06a2 236 if((currAngularVelocity * currAngularVelocity > 2 *
JesiMiranda 37:e0e6d3fe06a2 237 maxAngularDeceleration * angle) && (sensor3/10 <= arcLength + 10)) {
JesiMiranda 37:e0e6d3fe06a2 238 leftSafety = 1; //Not safe to turn left
JesiMiranda 37:e0e6d3fe06a2 239 out-> printf("Too fast to the left!\n");
JesiMiranda 37:e0e6d3fe06a2 240 }
JesiMiranda 37:e0e6d3fe06a2 241 else{
JesiMiranda 37:e0e6d3fe06a2 242 leftSafety = 0;
JesiMiranda 37:e0e6d3fe06a2 243 }
JesiMiranda 37:e0e6d3fe06a2 244 if((currAngularVelocity * currAngularVelocity > 2 *
JesiMiranda 37:e0e6d3fe06a2 245 maxAngularDeceleration * angle) && (sensor6/10 <= arcLength + 10)) {
JesiMiranda 37:e0e6d3fe06a2 246 rightSafety = 1; //Not safe to turn right
JesiMiranda 37:e0e6d3fe06a2 247 out-> printf("Too fast to the right!\n");
t1jain 34:b89967adc86c 248 }
JesiMiranda 37:e0e6d3fe06a2 249 else{
JesiMiranda 37:e0e6d3fe06a2 250 rightSafety = 0;
JesiMiranda 37:e0e6d3fe06a2 251 }
JesiMiranda 37:e0e6d3fe06a2 252
JesiMiranda 37:e0e6d3fe06a2 253 //Safe to continue turning
JesiMiranda 37:e0e6d3fe06a2 254 //Check if can turn left and back side sensors
t1jain 39:5438557a8b4e 255 // Staring t road and frequenctly checking
JesiMiranda 37:e0e6d3fe06a2 256 //Check the back sensor
JesiMiranda 37:e0e6d3fe06a2 257 /*int sensor7 = ToFV[0]; //back sensor NOTTT SURE
JesiMiranda 37:e0e6d3fe06a2 258 int sensor8 = ToFV[3]; //back sensor
JesiMiranda 37:e0e6d3fe06a2 259
JesiMiranda 37:e0e6d3fe06a2 260 if(curr_vel < 1 &&((2 * maxDecelerationSlow*sensor7 < curr_vel*curr_vel*1000*1000 ||
JesiMiranda 37:e0e6d3fe06a2 261 2 * maxDecelerationSlow*sensor8 < curr_vel*curr_vel*1000*1000) &&
JesiMiranda 37:e0e6d3fe06a2 262 (sensor7 < 1500 || sensor8 < 1500)) ||
JesiMiranda 37:e0e6d3fe06a2 263 550 > sensor7 || 550 > sensor8)
JesiMiranda 37:e0e6d3fe06a2 264 {
JesiMiranda 37:e0e6d3fe06a2 265 //out->printf("i am in danger\r\n");
JesiMiranda 37:e0e6d3fe06a2 266 if(x->read() > def)
JesiMiranda 37:e0e6d3fe06a2 267 {
JesiMiranda 37:e0e6d3fe06a2 268 x->write(def);
JesiMiranda 37:e0e6d3fe06a2 269 backwardSafety = 1;// You cannot move backward
JesiMiranda 37:e0e6d3fe06a2 270 }
JesiMiranda 37:e0e6d3fe06a2 271 }
JesiMiranda 37:e0e6d3fe06a2 272 //When going to fast to stop from wall
JesiMiranda 37:e0e6d3fe06a2 273 else if(curr_vel > 1 &&((2 * maxDecelerationFast*sensor7 < curr_vel*curr_vel*1000*1000 ||
JesiMiranda 37:e0e6d3fe06a2 274 2 * maxDecelerationFast*sensor8 < curr_vel*curr_vel*1000*1000) &&
JesiMiranda 37:e0e6d3fe06a2 275 (sensor7 < 1500 || sensor8 < 1500)) ||
JesiMiranda 37:e0e6d3fe06a2 276 550 > sensor7 || 550 > sensor8)
JesiMiranda 37:e0e6d3fe06a2 277 {
JesiMiranda 37:e0e6d3fe06a2 278 //out->printf("i am in danger\r\n");
JesiMiranda 37:e0e6d3fe06a2 279 if(x->read() > def)
JesiMiranda 37:e0e6d3fe06a2 280 {
JesiMiranda 37:e0e6d3fe06a2 281 x->write(def);
JesiMiranda 37:e0e6d3fe06a2 282 backwardSafety = 1;
JesiMiranda 37:e0e6d3fe06a2 283 }
JesiMiranda 37:e0e6d3fe06a2 284 }*/
JesiMiranda 37:e0e6d3fe06a2 285
JesiMiranda 37:e0e6d3fe06a2 286 /*Side Tof end*/
JesiMiranda 37:e0e6d3fe06a2 287
jvfausto 21:3489cffad196 288 }
ryanlin97 6:0cd57bdd8fbc 289
JesiMiranda 35:5a2fed4c2e9f 290 /*************************************************************************
JesiMiranda 35:5a2fed4c2e9f 291 * Constructor for Wheelchair class *
JesiMiranda 35:5a2fed4c2e9f 292 **************************************************************************/
JesiMiranda 35:5a2fed4c2e9f 293 Wheelchair::Wheelchair(PinName xPin, PinName yPin, Serial* pc, Timer* time, QEI* qei, QEI* qeiS,
JesiMiranda 35:5a2fed4c2e9f 294 VL53L1X** ToFT)
jvfausto 21:3489cffad196 295 {
jvfausto 21:3489cffad196 296 x_position = 0;
jvfausto 21:3489cffad196 297 y_position = 0;
jvfausto 21:3489cffad196 298 forwardSafety = 0;
t1jain 39:5438557a8b4e 299 backwardSafety = 0;
JesiMiranda 35:5a2fed4c2e9f 300
jvfausto 21:3489cffad196 301 /* Initializes X and Y variables to Pins */
JesiMiranda 35:5a2fed4c2e9f 302 x = new PwmOut(xPin);
jvfausto 21:3489cffad196 303 y = new PwmOut(yPin);
JesiMiranda 35:5a2fed4c2e9f 304
jvfausto 21:3489cffad196 305 /* Initializes IMU Library */
jvfausto 26:662693bd7f31 306 out = pc; // "out" is called for serial monitor
jvfausto 26:662693bd7f31 307 out->printf("on\r\n");
JesiMiranda 37:e0e6d3fe06a2 308 imu = new IMUWheelchair(pc, time);
jvfausto 21:3489cffad196 309 Wheelchair::stop(); // Wheelchair is initially stationary
jvfausto 21:3489cffad196 310 imu->setup(); // turns on the IMU
jvfausto 21:3489cffad196 311 wheelS = qeiS; // "wheel" is called for encoder
JesiMiranda 35:5a2fed4c2e9f 312 wheel = qei;
jvfausto 21:3489cffad196 313 ToF = ToFT; // passes pointer with addresses of ToF sensors
JesiMiranda 35:5a2fed4c2e9f 314
JesiMiranda 35:5a2fed4c2e9f 315 for(int i = 0; i < 12; i++) { // initializes the ToF Sensors
jvfausto 21:3489cffad196 316 (*(ToF+i))->initReading(0x31+((0x02)*i), 50000);
jvfausto 21:3489cffad196 317 }
JesiMiranda 35:5a2fed4c2e9f 318
jvfausto 21:3489cffad196 319 out->printf("wheelchair setup done \r\n"); // Make sure it initialized; prints in serial monitor
jvfausto 21:3489cffad196 320 ti = time;
JesiMiranda 35:5a2fed4c2e9f 321 for(int i = 0; i < 10; i++) {
JesiMiranda 35:5a2fed4c2e9f 322 (*(ToF+1))->readFromOneSensor();
JesiMiranda 35:5a2fed4c2e9f 323 (*(ToF+1))->readFromOneSensor();
t1jain 31:06f2362caf12 324 }
JesiMiranda 35:5a2fed4c2e9f 325 for(int i = 0; i < 150; i++) {
jvfausto 27:da718b990837 326 ledgeArrayLF[i] = (*(ToF+1))->readFromOneSensor();
t1jain 30:c25b2556e84d 327 ledgeArrayRF[i] = (*(ToF+4))->readFromOneSensor();
jvfausto 27:da718b990837 328 }
JesiMiranda 35:5a2fed4c2e9f 329
t1jain 30:c25b2556e84d 330 outlierToF[0] = LFTStats.mean() + 2*LFTStats.stdev();
t1jain 30:c25b2556e84d 331 outlierToF[1] = RFTStats.mean() + 2*RFTStats.stdev();
t1jain 34:b89967adc86c 332
jvfausto 21:3489cffad196 333 myPID.SetMode(AUTOMATIC); // PID mode: Automatic
jvfausto 21:3489cffad196 334 }
jvfausto 21:3489cffad196 335
JesiMiranda 35:5a2fed4c2e9f 336 /*************************************************************************
JesiMiranda 35:5a2fed4c2e9f 337 * Move wheelchair with joystick on manual mode *
JesiMiranda 35:5a2fed4c2e9f 338 **************************************************************************/
JesiMiranda 35:5a2fed4c2e9f 339 void Wheelchair::move(float x_coor, float y_coor)
jvfausto 21:3489cffad196 340 {
JesiMiranda 35:5a2fed4c2e9f 341 /* Scales one joystick measurement to the chair's joystick measurement */
ryanlin97 4:29a27953fe70 342 float scaled_x = ((x_coor * 1.6f) + 1.7f)/3.3f;
ryanlin97 4:29a27953fe70 343 float scaled_y = (3.3f - (y_coor * 1.6f))/3.3f;
jvfausto 21:3489cffad196 344
JesiMiranda 35:5a2fed4c2e9f 345 /* Sends the scaled joystic values to the chair */
JesiMiranda 35:5a2fed4c2e9f 346 x->write(scaled_x);
ryanlin97 4:29a27953fe70 347 y->write(scaled_y);
ryanlin97 5:e0ccaab3959a 348 }
JesiMiranda 35:5a2fed4c2e9f 349
JesiMiranda 35:5a2fed4c2e9f 350
JesiMiranda 35:5a2fed4c2e9f 351 /*************************************************************************
JesiMiranda 35:5a2fed4c2e9f 352 * Automatic mode: move forward and update x,y coordinate sent to chair *
JesiMiranda 35:5a2fed4c2e9f 353 **************************************************************************/
JesiMiranda 35:5a2fed4c2e9f 354 void Wheelchair::forward()
ryanlin97 1:c0beadca1617 355 {
jvfausto 26:662693bd7f31 356 //printf("current velosity; %f, curr vel S %f\r\n", curr_vel, curr_velS);
JesiMiranda 35:5a2fed4c2e9f 357 if(forwardSafety == 0) {
JesiMiranda 35:5a2fed4c2e9f 358 x->write(high);
JesiMiranda 35:5a2fed4c2e9f 359 y->write(def+offset);
jvfausto 21:3489cffad196 360 }
jvfausto 26:662693bd7f31 361 out->printf("%f, %f\r\n", curr_pos, wheelS->getDistance(53.975));
ryanlin97 0:fc0c4a184482 362 }
JesiMiranda 35:5a2fed4c2e9f 363
JesiMiranda 35:5a2fed4c2e9f 364 /*************************************************************************
JesiMiranda 35:5a2fed4c2e9f 365 * Automatic mode: move in reverse and update x,y coordinate sent to chair*
JesiMiranda 35:5a2fed4c2e9f 366 **************************************************************************/
JesiMiranda 35:5a2fed4c2e9f 367 void Wheelchair::backward()
ryanlin97 1:c0beadca1617 368 {
t1jain 39:5438557a8b4e 369 if (backwardSafety == 0) {
t1jain 39:5438557a8b4e 370 x->write(low);
t1jain 39:5438557a8b4e 371 y->write(def);
t1jain 39:5438557a8b4e 372 }
ryanlin97 0:fc0c4a184482 373 }
JesiMiranda 35:5a2fed4c2e9f 374 /*************************************************************************
JesiMiranda 35:5a2fed4c2e9f 375 * Automatic mode: move right and update x,y coordinate sent to chair *
JesiMiranda 35:5a2fed4c2e9f 376 **************************************************************************/
JesiMiranda 35:5a2fed4c2e9f 377 void Wheelchair::right()
ryanlin97 1:c0beadca1617 378 {
t1jain 34:b89967adc86c 379 //if safe to move, from ToFSafety
JesiMiranda 37:e0e6d3fe06a2 380 if(rightSafety == 0) {
JesiMiranda 35:5a2fed4c2e9f 381 x->write(def);
JesiMiranda 35:5a2fed4c2e9f 382 y->write(low);
t1jain 34:b89967adc86c 383 }
ryanlin97 0:fc0c4a184482 384 }
JesiMiranda 35:5a2fed4c2e9f 385 /*************************************************************************
JesiMiranda 35:5a2fed4c2e9f 386 * Automatic mode: move left and update x,y coordinate sent to chair *
JesiMiranda 35:5a2fed4c2e9f 387 **************************************************************************/
JesiMiranda 35:5a2fed4c2e9f 388 void Wheelchair::left()
ryanlin97 1:c0beadca1617 389 {
t1jain 34:b89967adc86c 390 //if safe to move, from ToFSafety
JesiMiranda 37:e0e6d3fe06a2 391 if(leftSafety == 0) {
t1jain 34:b89967adc86c 392 x->write(def);
t1jain 34:b89967adc86c 393 y->write(high);
t1jain 34:b89967adc86c 394 }
ryanlin97 0:fc0c4a184482 395 }
JesiMiranda 35:5a2fed4c2e9f 396 /*************************************************************************
JesiMiranda 35:5a2fed4c2e9f 397 * Stop the wheelchair *
JesiMiranda 35:5a2fed4c2e9f 398 **************************************************************************/
JesiMiranda 35:5a2fed4c2e9f 399 void Wheelchair::stop()
ryanlin97 1:c0beadca1617 400 {
ryanlin97 0:fc0c4a184482 401 x->write(def);
ryanlin97 0:fc0c4a184482 402 y->write(def);
ryanlin97 6:0cd57bdd8fbc 403 }
JesiMiranda 35:5a2fed4c2e9f 404 /*************************************************************************
JesiMiranda 35:5a2fed4c2e9f 405 * Counter-clockwise is ( - ) *
JesiMiranda 35:5a2fed4c2e9f 406 * Clockwise is ( + ) *
JesiMiranda 35:5a2fed4c2e9f 407 * Range of deg: 0 to 360 *
JesiMiranda 35:5a2fed4c2e9f 408 * This method takes in an angle from user and adjusts for turning right *
JesiMiranda 35:5a2fed4c2e9f 409 **************************************************************************/
jvfausto 21:3489cffad196 410 void Wheelchair::pid_right(int deg)
ryanlin97 12:921488918749 411 {
t1jain 33:f3585571f11e 412 bool overturn = false; // Boolean if angle over 360˚
JesiMiranda 35:5a2fed4c2e9f 413
JesiMiranda 35:5a2fed4c2e9f 414 out->printf("pid right\r\r\n");
jvfausto 21:3489cffad196 415 x->write(def); // Update x sent to chair to be stationary
jvfausto 21:3489cffad196 416 Setpoint = curr_yaw + deg; // Relative angle we want to turn
jvfausto 21:3489cffad196 417 pid_yaw = curr_yaw; // Sets pid_yaw to angle input from user
JesiMiranda 35:5a2fed4c2e9f 418
jvfausto 21:3489cffad196 419 /* Turns on overturn boolean if setpoint over 360˚ */
JesiMiranda 35:5a2fed4c2e9f 420 if(Setpoint > 360) {
ryanlin97 12:921488918749 421 overturn = true;
ryanlin97 12:921488918749 422 }
JesiMiranda 35:5a2fed4c2e9f 423
jvfausto 21:3489cffad196 424 myPID.SetTunings(5.5,0, 0.0035); // Sets the constants for P and D
jvfausto 21:3489cffad196 425 myPID.SetOutputLimits(0, def-low-.15); // Limit is set to the differnce between def and low
jvfausto 21:3489cffad196 426 myPID.SetControllerDirection(DIRECT); // PID mode: Direct
JesiMiranda 35:5a2fed4c2e9f 427
JesiMiranda 35:5a2fed4c2e9f 428 /* PID stops when approaching a litte less than desired angle */
JesiMiranda 35:5a2fed4c2e9f 429 while(pid_yaw < Setpoint - 3) {
jvfausto 21:3489cffad196 430 /* PID is set to correct angle range if angle greater than 360˚*/
JesiMiranda 35:5a2fed4c2e9f 431 if(overturn && curr_yaw < Setpoint-deg-1) {
JesiMiranda 35:5a2fed4c2e9f 432 pid_yaw = curr_yaw + 360;
JesiMiranda 35:5a2fed4c2e9f 433 } else {
jvfausto 17:7f3b69300bb6 434 pid_yaw = curr_yaw;
ryanlin97 12:921488918749 435 }
JesiMiranda 35:5a2fed4c2e9f 436
jvfausto 21:3489cffad196 437 myPID.Compute(); // Does PID calculations
jvfausto 21:3489cffad196 438 double tempor = -Output+def; // Temporary value with the voltage output
JesiMiranda 35:5a2fed4c2e9f 439 y->write(tempor); // Update y sent to chair
JesiMiranda 35:5a2fed4c2e9f 440
jvfausto 21:3489cffad196 441 /* Prints to serial monitor the current angle and setpoint */
JesiMiranda 35:5a2fed4c2e9f 442 out->printf("curr_yaw %f\r\r\n", curr_yaw);
jvfausto 21:3489cffad196 443 out->printf("Setpoint = %f \r\n", Setpoint);
JesiMiranda 35:5a2fed4c2e9f 444
jvfausto 21:3489cffad196 445 wait(.05); // Small delay (milliseconds)
ryanlin97 12:921488918749 446 }
JesiMiranda 35:5a2fed4c2e9f 447
jvfausto 21:3489cffad196 448 /* Saftey stop for wheelchair */
JesiMiranda 35:5a2fed4c2e9f 449 Wheelchair::stop();
jvfausto 21:3489cffad196 450 out->printf("done \r\n");
jvfausto 21:3489cffad196 451 }
JesiMiranda 35:5a2fed4c2e9f 452 /*************************************************************************
JesiMiranda 35:5a2fed4c2e9f 453 * Counter-clockwise is ( - ) *
JesiMiranda 35:5a2fed4c2e9f 454 * Clockwise is ( + ) *
JesiMiranda 35:5a2fed4c2e9f 455 * Range of deg: 0 to 360 *
JesiMiranda 35:5a2fed4c2e9f 456 * This method takes in an angle from user and adjusts for turning left *
JesiMiranda 35:5a2fed4c2e9f 457 **************************************************************************/
JesiMiranda 35:5a2fed4c2e9f 458 void Wheelchair::pid_left(int deg)
ryanlin97 12:921488918749 459 {
jvfausto 21:3489cffad196 460 bool overturn = false; //Boolean if angle under 0˚
JesiMiranda 35:5a2fed4c2e9f 461
JesiMiranda 35:5a2fed4c2e9f 462 out->printf("pid Left\r\r\n");
jvfausto 21:3489cffad196 463 x->write(def); // Update x sent to chair to be stationary
jvfausto 21:3489cffad196 464 Setpoint = curr_yaw - deg; // Relative angle we want to turn
jvfausto 21:3489cffad196 465 pid_yaw = curr_yaw; // Sets pid_yaw to angle input from user
JesiMiranda 35:5a2fed4c2e9f 466
jvfausto 21:3489cffad196 467 /* Turns on overturn boolean if setpoint less than 0˚ */
JesiMiranda 35:5a2fed4c2e9f 468 if(Setpoint < 0) {
ryanlin97 12:921488918749 469 overturn = true;
ryanlin97 12:921488918749 470 }
JesiMiranda 35:5a2fed4c2e9f 471
jvfausto 21:3489cffad196 472 myPID.SetTunings(5,0, 0.004); // Sets the constants for P and D
t1jain 33:f3585571f11e 473 myPID.SetOutputLimits(0,high-def-.12); // Limit is set to the differnce between def and low
jvfausto 21:3489cffad196 474 myPID.SetControllerDirection(REVERSE); // PID mode: Reverse
JesiMiranda 35:5a2fed4c2e9f 475
jvfausto 21:3489cffad196 476 /* PID stops when approaching a litte more than desired angle */
JesiMiranda 35:5a2fed4c2e9f 477 while(pid_yaw > Setpoint+3) {
JesiMiranda 35:5a2fed4c2e9f 478 /* PID is set to correct angle range if angle less than 0˚ */
JesiMiranda 35:5a2fed4c2e9f 479 if(overturn && curr_yaw > Setpoint+deg+1) {
JesiMiranda 35:5a2fed4c2e9f 480 pid_yaw = curr_yaw - 360;
JesiMiranda 35:5a2fed4c2e9f 481 } else {
JesiMiranda 35:5a2fed4c2e9f 482 pid_yaw = curr_yaw;
JesiMiranda 35:5a2fed4c2e9f 483 }
JesiMiranda 35:5a2fed4c2e9f 484
jvfausto 21:3489cffad196 485 myPID.Compute(); // Does PID calculations
jvfausto 21:3489cffad196 486 double tempor = Output+def; // Temporary value with the voltage output
jvfausto 21:3489cffad196 487 y->write(tempor); // Update y sent to chair
JesiMiranda 35:5a2fed4c2e9f 488
jvfausto 21:3489cffad196 489 /* Prints to serial monitor the current angle and setpoint */
jvfausto 17:7f3b69300bb6 490 out->printf("curr_yaw %f\r\n", curr_yaw);
jvfausto 21:3489cffad196 491 out->printf("Setpoint = %f \r\n", Setpoint);
JesiMiranda 35:5a2fed4c2e9f 492
jvfausto 21:3489cffad196 493 wait(.05); // Small delay (milliseconds)
ryanlin97 12:921488918749 494 }
JesiMiranda 35:5a2fed4c2e9f 495
JesiMiranda 35:5a2fed4c2e9f 496 /* Saftey stop for wheelchair */
JesiMiranda 35:5a2fed4c2e9f 497 Wheelchair::stop();
jvfausto 21:3489cffad196 498 out->printf("done \r\n");
ryanlin97 12:921488918749 499
jvfausto 21:3489cffad196 500 }
JesiMiranda 35:5a2fed4c2e9f 501
JesiMiranda 35:5a2fed4c2e9f 502 /*************************************************************************
JesiMiranda 35:5a2fed4c2e9f 503 * This method determines whether to turn left or right *
JesiMiranda 35:5a2fed4c2e9f 504 **************************************************************************/
JesiMiranda 35:5a2fed4c2e9f 505 void Wheelchair::pid_turn(int deg)
JesiMiranda 35:5a2fed4c2e9f 506 {
JesiMiranda 35:5a2fed4c2e9f 507
JesiMiranda 35:5a2fed4c2e9f 508 /*****************************************************************
JesiMiranda 35:5a2fed4c2e9f 509 * Sets angle to coterminal angle for left turn if deg > 180 *
JesiMiranda 35:5a2fed4c2e9f 510 * Sets angle to coterminal angle for right turn if deg < -180 *
JesiMiranda 35:5a2fed4c2e9f 511 *****************************************************************/
JesiMiranda 35:5a2fed4c2e9f 512 if(deg > 180) {
ryanlin97 12:921488918749 513 deg -= 360;
JesiMiranda 35:5a2fed4c2e9f 514 } else if(deg < -180) {
JesiMiranda 35:5a2fed4c2e9f 515 deg +=360;
ryanlin97 12:921488918749 516 }
JesiMiranda 35:5a2fed4c2e9f 517
jvfausto 21:3489cffad196 518 /* Makes sure angle inputted to function is positive */
ryanlin97 12:921488918749 519 int turnAmt = abs(deg);
JesiMiranda 35:5a2fed4c2e9f 520
jvfausto 21:3489cffad196 521 /* Calls PID_right if deg > 0, else calls PID_left if deg < 0 */
JesiMiranda 35:5a2fed4c2e9f 522 if(deg >= 0) {
JesiMiranda 35:5a2fed4c2e9f 523 Wheelchair::pid_right(turnAmt);
JesiMiranda 35:5a2fed4c2e9f 524 } else {
JesiMiranda 35:5a2fed4c2e9f 525 Wheelchair::pid_left(turnAmt);
jvfausto 21:3489cffad196 526 }
ryanlin97 12:921488918749 527
jvfausto 21:3489cffad196 528 }
jvfausto 21:3489cffad196 529
JesiMiranda 35:5a2fed4c2e9f 530 /*************************************************************************
JesiMiranda 35:5a2fed4c2e9f 531 * This method takes in distance to travel and adjust to move forward *
JesiMiranda 35:5a2fed4c2e9f 532 **************************************************************************/
jvfausto 19:71a6621ee5c3 533 void Wheelchair::pid_forward(double mm)
jvfausto 17:7f3b69300bb6 534 {
jvfausto 21:3489cffad196 535 mm -= 20; // Makes sure distance does not overshoot
jvfausto 21:3489cffad196 536 Input = 0; // Initializes input to zero: Test latter w/o
jvfausto 21:3489cffad196 537 wheel->reset(); // Resets encoders so that they start at 0
JesiMiranda 35:5a2fed4c2e9f 538
jvfausto 17:7f3b69300bb6 539 out->printf("pid foward\r\n");
JesiMiranda 35:5a2fed4c2e9f 540
jvfausto 21:3489cffad196 541 double tempor; // Initializes Temporary variable for x input
jvfausto 21:3489cffad196 542 Setpoint = mm; // Initializes the setpoint to desired value
JesiMiranda 35:5a2fed4c2e9f 543
jvfausto 21:3489cffad196 544 myPIDDistance.SetTunings(5.5,0, 0.0015); // Sets constants for P and D
JesiMiranda 35:5a2fed4c2e9f 545 myPIDDistance.SetOutputLimits(0,high-def-.15); // Limit set to difference between high and def
jvfausto 21:3489cffad196 546 myPIDDistance.SetControllerDirection(DIRECT); // PID mode: Direct
JesiMiranda 35:5a2fed4c2e9f 547
jvfausto 21:3489cffad196 548 y->write(def+offset); // Update y to make chair stationary
JesiMiranda 35:5a2fed4c2e9f 549
jvfausto 21:3489cffad196 550 /* Chair stops moving when Setpoint is reached */
JesiMiranda 35:5a2fed4c2e9f 551 while(Input < Setpoint) {
JesiMiranda 35:5a2fed4c2e9f 552
JesiMiranda 35:5a2fed4c2e9f 553 if(out->readable()) { // Emergency Break
jvfausto 21:3489cffad196 554 break;
jvfausto 21:3489cffad196 555 }
jvfausto 17:7f3b69300bb6 556
jvfausto 21:3489cffad196 557 Input = wheel->getDistance(53.975); // Gets distance from Encoder into PID
jvfausto 21:3489cffad196 558 wait(.05); // Slight Delay: *****Test without
jvfausto 21:3489cffad196 559 myPIDDistance.Compute(); // Compute distance traveled by chair
JesiMiranda 35:5a2fed4c2e9f 560
JesiMiranda 35:5a2fed4c2e9f 561 tempor = Output + def; // Temporary output variable
jvfausto 21:3489cffad196 562 x->write(tempor); // Update x sent to chair
jvfausto 17:7f3b69300bb6 563
jvfausto 21:3489cffad196 564 /* Prints to serial monitor the distance traveled by chair */
jvfausto 19:71a6621ee5c3 565 out->printf("distance %f\r\n", Input);
JesiMiranda 35:5a2fed4c2e9f 566 }
JesiMiranda 35:5a2fed4c2e9f 567
JesiMiranda 35:5a2fed4c2e9f 568 }
jvfausto 21:3489cffad196 569
JesiMiranda 35:5a2fed4c2e9f 570 /*************************************************************************
JesiMiranda 35:5a2fed4c2e9f 571 * This method returns the relative angular position of chair *
JesiMiranda 35:5a2fed4c2e9f 572 **************************************************************************/
jvfausto 21:3489cffad196 573 double Wheelchair::getTwistZ()
jvfausto 17:7f3b69300bb6 574 {
jvfausto 21:3489cffad196 575 return imu->gyro_z();
JesiMiranda 35:5a2fed4c2e9f 576 }
jvfausto 18:663b6d693252 577
JesiMiranda 35:5a2fed4c2e9f 578 /*************************************************************************
JesiMiranda 35:5a2fed4c2e9f 579 * This method computes the relative angle for Twist message in ROS *
JesiMiranda 35:5a2fed4c2e9f 580 **************************************************************************/
jvfausto 21:3489cffad196 581 void Wheelchair::pid_twistA()
jvfausto 21:3489cffad196 582 {
jvfausto 21:3489cffad196 583 /* Initialize variables for angle and update x,y sent to chair */
jvfausto 21:3489cffad196 584 char c;
jvfausto 21:3489cffad196 585 double temporA = def;
JesiMiranda 35:5a2fed4c2e9f 586 y->write(def);
JesiMiranda 35:5a2fed4c2e9f 587 x->write(def);
JesiMiranda 35:5a2fed4c2e9f 588
jvfausto 21:3489cffad196 589 PIDAngularV.SetTunings(.00015,0, 0.00); // Sets the constants for P and D
jvfausto 21:3489cffad196 590 PIDAngularV.SetOutputLimits(-.1, .1); // Limit set to be in range specified
jvfausto 21:3489cffad196 591 PIDAngularV.SetControllerDirection(DIRECT); // PID mode: Direct
JesiMiranda 35:5a2fed4c2e9f 592
jvfausto 21:3489cffad196 593 /* Computes angular position of wheelchair while turning */
JesiMiranda 35:5a2fed4c2e9f 594 while(1) {
jvfausto 21:3489cffad196 595 yDesired = angularV;
JesiMiranda 35:5a2fed4c2e9f 596
jvfausto 21:3489cffad196 597 /* Update and set all variable so that the chair is stationary
jvfausto 21:3489cffad196 598 * if the desired angle is zero
jvfausto 21:3489cffad196 599 */
JesiMiranda 35:5a2fed4c2e9f 600 if(yDesired == 0) {
jvfausto 21:3489cffad196 601 x->write(def);
jvfausto 21:3489cffad196 602 y->write(def);
jvfausto 21:3489cffad196 603 yDesired = 0;
ryanlin97 8:381a4ec3fef8 604 return;
ryanlin97 7:5e38d43fbce3 605 }
JesiMiranda 35:5a2fed4c2e9f 606
jvfausto 21:3489cffad196 607 /* Continuously updates with current angle measured by IMU */
JesiMiranda 35:5a2fed4c2e9f 608 yIn = imu->gyro_z();
jvfausto 21:3489cffad196 609 PIDAngularV.Compute();
jvfausto 21:3489cffad196 610 temporA += yOut; // Temporary value with the voltage output
jvfausto 21:3489cffad196 611 y->write(temporA); // Update y sent to chair
JesiMiranda 35:5a2fed4c2e9f 612
jvfausto 21:3489cffad196 613 //out->printf("temporA: %f, yDesired %f, angle: %f\r\n", temporA, yDesired, imu->gyro_z());
jvfausto 21:3489cffad196 614 wait(.05); // Small delay (milliseconds)
ryanlin97 6:0cd57bdd8fbc 615 }
JesiMiranda 35:5a2fed4c2e9f 616
JesiMiranda 35:5a2fed4c2e9f 617 }
ryanlin97 6:0cd57bdd8fbc 618
JesiMiranda 35:5a2fed4c2e9f 619 /*************************************************************************
JesiMiranda 35:5a2fed4c2e9f 620 * This method computes the relative velocity for Twist message in ROS *
JesiMiranda 35:5a2fed4c2e9f 621 **************************************************************************/
jvfausto 21:3489cffad196 622 void Wheelchair::pid_twistV()
ryanlin97 6:0cd57bdd8fbc 623 {
jvfausto 21:3489cffad196 624 /* Initializes variables as default */
jvfausto 21:3489cffad196 625 double temporV = def;
jvfausto 26:662693bd7f31 626 double temporS = def+offset;
jvfausto 21:3489cffad196 627 vDesiredS = 0;
jvfausto 21:3489cffad196 628 x->write(def);
jvfausto 21:3489cffad196 629 y->write(def);
jvfausto 21:3489cffad196 630 wheel->reset(); // Resets the encoders
jvfausto 21:3489cffad196 631 /* Sets the constants for P and D */
JesiMiranda 35:5a2fed4c2e9f 632 PIDVelosity.SetTunings(.0005,0, 0.00);
JesiMiranda 35:5a2fed4c2e9f 633 PIDSlaveV.SetTunings(.005,0.000001, 0.000001);
JesiMiranda 35:5a2fed4c2e9f 634
jvfausto 21:3489cffad196 635 /* Limits to the range specified */
JesiMiranda 35:5a2fed4c2e9f 636 PIDVelosity.SetOutputLimits(-.005, .005);
JesiMiranda 35:5a2fed4c2e9f 637 PIDSlaveV.SetOutputLimits(-.002, .002);
JesiMiranda 35:5a2fed4c2e9f 638
jvfausto 21:3489cffad196 639 /* PID mode: Direct */
JesiMiranda 35:5a2fed4c2e9f 640 PIDVelosity.SetControllerDirection(DIRECT);
JesiMiranda 35:5a2fed4c2e9f 641 PIDSlaveV.SetControllerDirection(DIRECT);
JesiMiranda 35:5a2fed4c2e9f 642
JesiMiranda 35:5a2fed4c2e9f 643 while(1) {
jvfausto 21:3489cffad196 644 linearV = .7;
jvfausto 21:3489cffad196 645 test1 = linearV*100;
jvfausto 21:3489cffad196 646 vel = curr_vel;
jvfausto 21:3489cffad196 647 vDesired = linearV*100;
jvfausto 21:3489cffad196 648 if(out->readable())
jvfausto 21:3489cffad196 649 return;
JesiMiranda 35:5a2fed4c2e9f 650 /* Update and set all variable so that the chair is stationary
JesiMiranda 35:5a2fed4c2e9f 651 * if the velocity is zero
JesiMiranda 35:5a2fed4c2e9f 652 */
JesiMiranda 35:5a2fed4c2e9f 653 if(linearV == 0) {
jvfausto 21:3489cffad196 654 x->write(def);
jvfausto 21:3489cffad196 655 y->write(def);
ryanlin97 8:381a4ec3fef8 656
jvfausto 21:3489cffad196 657 vel = 0;
jvfausto 21:3489cffad196 658 vDesired = 0;
jvfausto 21:3489cffad196 659 dist_old = 0;
ryanlin97 8:381a4ec3fef8 660 return;
ryanlin97 8:381a4ec3fef8 661 }
JesiMiranda 35:5a2fed4c2e9f 662
JesiMiranda 35:5a2fed4c2e9f 663 if(vDesired >= 0) {
jvfausto 21:3489cffad196 664 PIDVelosity.SetTunings(.000004,0, 0.00); // Sets the constants for P and D
jvfausto 21:3489cffad196 665 PIDVelosity.SetOutputLimits(-.002, .002); // Limits to the range specified
JesiMiranda 35:5a2fed4c2e9f 666 } else {
jvfausto 21:3489cffad196 667 PIDVelosity.SetTunings(.000015,0, 0.00); // Sets the constants for P and D
jvfausto 21:3489cffad196 668 PIDVelosity.SetOutputLimits(-.0005, .0005); // Limits to range specified
JesiMiranda 35:5a2fed4c2e9f 669 }
JesiMiranda 35:5a2fed4c2e9f 670
jvfausto 21:3489cffad196 671 /* Sets maximum value of variable to 1 */
JesiMiranda 35:5a2fed4c2e9f 672 if(temporV >= 1.5) {
jvfausto 21:3489cffad196 673 temporV = 1.5;
ryanlin97 8:381a4ec3fef8 674 }
jvfausto 21:3489cffad196 675 /* Scales and makes some adjustments to velocity */
jvfausto 21:3489cffad196 676 vIn = curr_vel*100;
jvfausto 21:3489cffad196 677 vInS = curr_vel-curr_velS;
jvfausto 21:3489cffad196 678 PIDVelosity.Compute();
jvfausto 21:3489cffad196 679 PIDSlaveV.Compute();
JesiMiranda 35:5a2fed4c2e9f 680 if(forwardSafety == 0) {
JesiMiranda 35:5a2fed4c2e9f 681 temporV += vOut;
JesiMiranda 35:5a2fed4c2e9f 682 temporS += vOutS;
JesiMiranda 35:5a2fed4c2e9f 683
JesiMiranda 35:5a2fed4c2e9f 684 /* Updates x,y sent to Wheelchair and for Odometry message in ROS */
JesiMiranda 35:5a2fed4c2e9f 685 x->write(temporV);
JesiMiranda 35:5a2fed4c2e9f 686 test2 = temporV;
JesiMiranda 35:5a2fed4c2e9f 687 y->write(temporS);
JesiMiranda 35:5a2fed4c2e9f 688 } else {
jvfausto 21:3489cffad196 689 x->write(def);
jvfausto 21:3489cffad196 690 y->write(def);
jvfausto 21:3489cffad196 691 }
jvfausto 21:3489cffad196 692 //out->printf("Velosity: %f, Velosity2: %f, temporV %f, temporS %f\r\n", curr_vel, curr_velS, temporV, temporS);
jvfausto 21:3489cffad196 693 Wheelchair::odomMsg();
jvfausto 21:3489cffad196 694 wait(.01); // Small delay (milliseconds)
ryanlin97 6:0cd57bdd8fbc 695 }
ryanlin97 11:d14a1f7f1297 696 }
ryanlin97 11:d14a1f7f1297 697
JesiMiranda 35:5a2fed4c2e9f 698 /*************************************************************************
JesiMiranda 35:5a2fed4c2e9f 699 * This method calculates the relative position of the chair everytime the*
JesiMiranda 35:5a2fed4c2e9f 700 * encoders reset by setting its old position as the origin to calculate *
JesiMiranda 35:5a2fed4c2e9f 701 * the new position *
JesiMiranda 35:5a2fed4c2e9f 702 **************************************************************************/
jvfausto 21:3489cffad196 703 void Wheelchair::odomMsg()
ryanlin97 11:d14a1f7f1297 704 {
jvfausto 21:3489cffad196 705 double dist_new = curr_pos;
jvfausto 21:3489cffad196 706 double dist = dist_new-dist_old;
jvfausto 21:3489cffad196 707 double temp_x = dist*sin(z_angular*3.14159/180);
jvfausto 21:3489cffad196 708 double temp_y = dist*cos(z_angular*3.14159/180);
JesiMiranda 35:5a2fed4c2e9f 709
jvfausto 21:3489cffad196 710 x_position += temp_x;
jvfausto 21:3489cffad196 711 y_position += temp_y;
JesiMiranda 35:5a2fed4c2e9f 712
jvfausto 21:3489cffad196 713 dist_old = dist_new;
JesiMiranda 35:5a2fed4c2e9f 714 }
jvfausto 21:3489cffad196 715
JesiMiranda 35:5a2fed4c2e9f 716 /**************************************************************************
JesiMiranda 35:5a2fed4c2e9f 717 * This method prints the Odometry message to the serial monitor *
JesiMiranda 35:5a2fed4c2e9f 718 ***************************************************************************/
JesiMiranda 35:5a2fed4c2e9f 719 void Wheelchair::showOdom()
JesiMiranda 35:5a2fed4c2e9f 720 {
JesiMiranda 35:5a2fed4c2e9f 721 out->printf("x %f, y %f, angle %f", x_position, y_position, z_angular);
JesiMiranda 35:5a2fed4c2e9f 722 }
jvfausto 21:3489cffad196 723
JesiMiranda 35:5a2fed4c2e9f 724 /**************************************************************************
JesiMiranda 35:5a2fed4c2e9f 725 * This method returns the approximate distance based on the wheel diameter*
JesiMiranda 35:5a2fed4c2e9f 726 ***************************************************************************/
jvfausto 21:3489cffad196 727 float Wheelchair::getDistance()
jvfausto 21:3489cffad196 728 {
jvfausto 21:3489cffad196 729 return wheel->getDistance(Diameter);
ryanlin97 6:0cd57bdd8fbc 730 }
ryanlin97 8:381a4ec3fef8 731
JesiMiranda 35:5a2fed4c2e9f 732 /**************************************************************************
JesiMiranda 35:5a2fed4c2e9f 733 * This method resets the Encoder's *
JesiMiranda 35:5a2fed4c2e9f 734 ***************************************************************************/
jvfausto 21:3489cffad196 735 void Wheelchair::resetDistance()
jvfausto 21:3489cffad196 736 {
ryanlin97 12:921488918749 737 wheel->reset();
jvfausto 21:3489cffad196 738 }
jvfausto 21:3489cffad196 739
JesiMiranda 35:5a2fed4c2e9f 740 /*---------------------------------------------------------------------------------------------------*/
JesiMiranda 35:5a2fed4c2e9f 741 /*---------------------------------------------------------------------------------------------------*/
JesiMiranda 35:5a2fed4c2e9f 742 /*---------------------------------------------------------------------------------------------------*/
JesiMiranda 35:5a2fed4c2e9f 743 /*---------------------------------------------------------------------------------------------------*/
JesiMiranda 35:5a2fed4c2e9f 744 /*---------------------------------------------------------------------------------------------------*/
jvfausto 21:3489cffad196 745
JesiMiranda 35:5a2fed4c2e9f 746 /*Predetermined paths For Demmo*/
JesiMiranda 35:5a2fed4c2e9f 747 void Wheelchair::desk()
jvfausto 21:3489cffad196 748 {
jvfausto 19:71a6621ee5c3 749 Wheelchair::pid_forward(5461);
jvfausto 19:71a6621ee5c3 750 Wheelchair::pid_right(87);
jvfausto 19:71a6621ee5c3 751 Wheelchair::pid_forward(3658);
jvfausto 19:71a6621ee5c3 752 Wheelchair::pid_right(87);
jvfausto 19:71a6621ee5c3 753 Wheelchair::pid_forward(3658);
jvfausto 21:3489cffad196 754 }
JesiMiranda 35:5a2fed4c2e9f 755
JesiMiranda 35:5a2fed4c2e9f 756 void Wheelchair::kitchen()
jvfausto 21:3489cffad196 757 {
jvfausto 19:71a6621ee5c3 758 Wheelchair::pid_forward(5461);
jvfausto 20:f42db4ae16f0 759 Wheelchair::pid_right(87);
jvfausto 19:71a6621ee5c3 760 Wheelchair::pid_forward(3658);
jvfausto 19:71a6621ee5c3 761 Wheelchair::pid_left(90);
jvfausto 19:71a6621ee5c3 762 Wheelchair::pid_forward(305);
jvfausto 21:3489cffad196 763 }
JesiMiranda 35:5a2fed4c2e9f 764
jvfausto 21:3489cffad196 765 void Wheelchair::desk_to_kitchen()
jvfausto 21:3489cffad196 766 {
jvfausto 19:71a6621ee5c3 767 Wheelchair::pid_right(180);
jvfausto 19:71a6621ee5c3 768 Wheelchair::pid_forward(3700);
jvfausto 21:3489cffad196 769 }