added code for PCB on and off, added pointers to e_button and pwm pins

Dependencies:   QEI2 chair_BNO055 PID VL53L1X_Filter

Dependents:   wheelchairControlSumer2019

Committer:
JesiMiranda
Date:
Fri Jun 28 19:35:51 2019 +0000
Revision:
28:ad02cb329fe3
Parent:
27:0b1a837f123c
added code for PCB on and off, added pointers to e_button and pwm pins

Who changed what in which revision?

UserRevisionLine numberNew contents of line
ryanlin97 0:fc0c4a184482 1 #ifndef wheelchair
ryanlin97 0:fc0c4a184482 2 #define wheelchair
ryanlin97 0:fc0c4a184482 3
jvfausto 21:3489cffad196 4 /* Importing libraries into wheelchair.h */
ryanlin97 11:d14a1f7f1297 5 #include "chair_BNO055.h"
jvfausto 17:7f3b69300bb6 6 #include "PID.h"
ryanlin97 12:921488918749 7 #include "QEI.h"
jvfausto 21:3489cffad196 8 #include "VL53L1X.h"
jvfausto 21:3489cffad196 9
ryanlin97 16:b403082eeacd 10 #include <ros.h>
ryanlin97 16:b403082eeacd 11 #include <geometry_msgs/Twist.h>
jvfausto 21:3489cffad196 12 #include <nav_msgs/Odometry.h>
ryanlin97 12:921488918749 13
ryanlin97 0:fc0c4a184482 14
jvfausto 21:3489cffad196 15 /*
jvfausto 21:3489cffad196 16 * Joystick has analog out of 200-700, scale values between 1.3 and 3.3
JesiMiranda 28:ad02cb329fe3 17 */
jvfausto 21:3489cffad196 18 #define def (2.5f/3.3f) //Default axis on joystick to stay neutral; used on x and y axis
jvfausto 21:3489cffad196 19 #define high 3.3f/3.3f //High power on joystick; used on x and y axis
jvfausto 21:3489cffad196 20 #define low (1.7f/3.3f) //Low power on joystick; used on x and y axis
jvfausto 26:662693bd7f31 21 #define offset .03f //Joystick adjustment to be able to go straight. Chair dependent on manufactoring precision
jvfausto 21:3489cffad196 22 #define process .1 //Defines default time delay in seconds
ryanlin97 14:9caca9fde9b0 23
jvfausto 21:3489cffad196 24 /* Pin plug in for Nucleo-L432KC */
jvfausto 21:3489cffad196 25 #define xDir PA_6 //* PWM Pins */
jvfausto 21:3489cffad196 26 #define yDir PA_5
jvfausto 21:3489cffad196 27 #define Encoder1 D7 //*Digital In Pull Up Pin */
jvfausto 21:3489cffad196 28 #define Encoder2 D8
jvfausto 21:3489cffad196 29 #define Diameter 31.75 //Diameter of encoder wheel
jvfausto 26:662693bd7f31 30 #define maxDecelerationSlow 120
jvfausto 26:662693bd7f31 31 #define maxDecelerationFast 30
jvfausto 21:3489cffad196 32 #define ToFSensorNum 12
ryanlin97 14:9caca9fde9b0 33
ryanlin97 12:921488918749 34 /** Wheelchair class
ryanlin97 12:921488918749 35 * Used for controlling the smart wheelchair
ryanlin97 12:921488918749 36 */
jvfausto 17:7f3b69300bb6 37
ryanlin97 0:fc0c4a184482 38 class Wheelchair
ryanlin97 0:fc0c4a184482 39 {
ryanlin97 0:fc0c4a184482 40 public:
ryanlin97 12:921488918749 41 /** Create Wheelchair Object with x,y pin for analog dc output
ryanlin97 12:921488918749 42 * serial for printout, and timer
ryanlin97 12:921488918749 43 */
jvfausto 21:3489cffad196 44 Wheelchair(PinName xPin, PinName yPin, Serial* pc, Timer* time, QEI* wheel, QEI* wheelS,
JesiMiranda 28:ad02cb329fe3 45 VL53L1X** ToF);
JesiMiranda 28:ad02cb329fe3 46
jvfausto 21:3489cffad196 47 /** Move using the joystick */
ryanlin97 3:a5e71bfdb492 48 void move(float x_coor, float y_coor);
JesiMiranda 28:ad02cb329fe3 49
jvfausto 21:3489cffad196 50 /* Turn right a certain amount of degrees using PID*/
ryanlin97 12:921488918749 51 void pid_right(int deg);
JesiMiranda 28:ad02cb329fe3 52
jvfausto 21:3489cffad196 53 /* Turn left a certain amount of degrees using PID*/
ryanlin97 12:921488918749 54 void pid_left(int deg);
JesiMiranda 28:ad02cb329fe3 55
jvfausto 21:3489cffad196 56 /* Drive the wheelchair forward */
ryanlin97 1:c0beadca1617 57 void forward();
JesiMiranda 28:ad02cb329fe3 58
jvfausto 21:3489cffad196 59 /* Drive the wheelchair in reverse*/
ryanlin97 1:c0beadca1617 60 void backward();
JesiMiranda 28:ad02cb329fe3 61
jvfausto 21:3489cffad196 62 /* Turn the wheelchair right*/
ryanlin97 1:c0beadca1617 63 void right();
JesiMiranda 28:ad02cb329fe3 64
jvfausto 21:3489cffad196 65 /* Turn the wheelchair left*/
ryanlin97 1:c0beadca1617 66 void left();
JesiMiranda 28:ad02cb329fe3 67
jvfausto 21:3489cffad196 68 /* Stop the wheelchair*/
ryanlin97 1:c0beadca1617 69 void stop();
JesiMiranda 28:ad02cb329fe3 70
jvfausto 21:3489cffad196 71 /* Functions to get IMU data*/
ryanlin97 11:d14a1f7f1297 72 void compass_thread();
jvfausto 21:3489cffad196 73 void velocity_thread();
jvfausto 21:3489cffad196 74 void rosCom_thread();
jvfausto 21:3489cffad196 75 void assistSafe_thread();
t1jain 27:0b1a837f123c 76 void emergencyButton_thread();
JesiMiranda 28:ad02cb329fe3 77
jvfausto 21:3489cffad196 78 /* Move x millimiters foward using PID*/
jvfausto 19:71a6621ee5c3 79 void pid_forward(double mm);
JesiMiranda 28:ad02cb329fe3 80
jvfausto 21:3489cffad196 81 /* Obtain angular position for Twist message */
jvfausto 21:3489cffad196 82 double getTwistZ();
JesiMiranda 28:ad02cb329fe3 83
jvfausto 21:3489cffad196 84 /* Gets the encoder distance moved since encoder reset*/
ryanlin97 12:921488918749 85 float getDistance();
JesiMiranda 28:ad02cb329fe3 86
jvfausto 21:3489cffad196 87 /* Resets encoder*/
ryanlin97 12:921488918749 88 void resetDistance();
JesiMiranda 28:ad02cb329fe3 89
jvfausto 21:3489cffad196 90 /* Function to determine whether we are turning left or right*/
ryanlin97 12:921488918749 91 void pid_turn(int deg);
JesiMiranda 28:ad02cb329fe3 92
jvfausto 21:3489cffad196 93 /* Function to obtain angular and linear velocity */
jvfausto 21:3489cffad196 94 void pid_twistA();
jvfausto 21:3489cffad196 95 void pid_twistV();
JesiMiranda 28:ad02cb329fe3 96
jvfausto 21:3489cffad196 97 /* Function to publish and show Odometry message */
jvfausto 21:3489cffad196 98 void odomMsg();
jvfausto 21:3489cffad196 99 void showOdom();
JesiMiranda 28:ad02cb329fe3 100
jvfausto 21:3489cffad196 101 /* Functions with a predetermined path (demo) */
jvfausto 19:71a6621ee5c3 102 void desk();
jvfausto 19:71a6621ee5c3 103 void kitchen();
jvfausto 19:71a6621ee5c3 104 void desk_to_kitchen();
JesiMiranda 28:ad02cb329fe3 105
jvfausto 21:3489cffad196 106 /* Variables for postion, angle, and velocity */
jvfausto 21:3489cffad196 107 double x_position;
jvfausto 21:3489cffad196 108 double y_position;
JesiMiranda 28:ad02cb329fe3 109 double z_angular;
jvfausto 21:3489cffad196 110 double curr_vel;
jvfausto 21:3489cffad196 111 double z_twistA;
jvfausto 21:3489cffad196 112 double linearV;
jvfausto 21:3489cffad196 113 double angularV;
jvfausto 21:3489cffad196 114 double vel;
JesiMiranda 28:ad02cb329fe3 115 double test1, test2;
jvfausto 21:3489cffad196 116 bool forwardSafety;
jvfausto 21:3489cffad196 117 double curr_yaw, curr_velS; // Variable that contains current relative angle
jvfausto 21:3489cffad196 118
JesiMiranda 28:ad02cb329fe3 119
ryanlin97 1:c0beadca1617 120 private:
jvfausto 21:3489cffad196 121 /* Pointers for the joystick speed */
ryanlin97 3:a5e71bfdb492 122 PwmOut* x;
ryanlin97 3:a5e71bfdb492 123 PwmOut* y;
JesiMiranda 28:ad02cb329fe3 124 //Pointers for PCB
JesiMiranda 28:ad02cb329fe3 125 PwmOut* on;
JesiMiranda 28:ad02cb329fe3 126 PwmOut* off;
jvfausto 21:3489cffad196 127
JesiMiranda 28:ad02cb329fe3 128 DigitalIn* e_button; //Pointer to e_button
JesiMiranda 28:ad02cb329fe3 129
jvfausto 21:3489cffad196 130 chair_BNO055* imu; // Pointer to IMU
jvfausto 21:3489cffad196 131 Serial* out; // Pointer to Serial Monitor
jvfausto 21:3489cffad196 132 Timer* ti; // Pointer to the timer
jvfausto 21:3489cffad196 133 QEI* wheel; // Pointer to encoder
jvfausto 21:3489cffad196 134 QEI* wheelS; // Pointer to encoder
jvfausto 21:3489cffad196 135 VL53L1X** ToF; // Arrays of pointers to ToF sensors
ryanlin97 1:c0beadca1617 136
JesiMiranda 28:ad02cb329fe3 137
ryanlin97 0:fc0c4a184482 138 };
ryanlin97 0:fc0c4a184482 139 #endif