Added more code for side and angled sensor

Dependencies:   QEI2 PID Watchdog VL53L1X_Filter BNOWrapper ros_lib_kinetic

Committer:
t1jain
Date:
Wed Aug 07 19:01:17 2019 +0000
Revision:
42:62c49ad06707
Parent:
41:1a687bcf4b0a
Child:
43:9858a580b3d7
Changed references from MPU6050 to BNO080

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