Added more code for side and angled sensor

Dependencies:   QEI2 PID Watchdog VL53L1X_Filter BNOWrapper ros_lib_kinetic

Committer:
JesiMiranda
Date:
Tue Jul 09 21:18:01 2019 +0000
Revision:
35:5a2fed4c2e9f
Parent:
34:b89967adc86c
Child:
37:e0e6d3fe06a2
finished commenting on the .cpp file and changed the statistics library name

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