Where we will test the side ToF sensors

Dependencies:   QEI2 PID Watchdog VL53L1X_Filter ros_lib_kinetic

Committer:
isagmz
Date:
Tue Jul 02 21:17:03 2019 +0000
Revision:
20:3c1b58654e67
Parent:
18:a10277a63b53
Child:
21:d1faccb96146
to share

Who changed what in which revision?

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