Revised for integration

Dependencies:   QEI2 chair_BNO055 PID VL53L1X_Filter

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers wheelchair.h Source File

wheelchair.h

00001 #ifndef wheelchair
00002 #define wheelchair
00003 
00004 /* Importing libraries into wheelchair.h */
00005 #include "chair_BNO055.h"
00006 #include "PID.h"
00007 #include "QEI.h"
00008 #include "VL53L1X.h"
00009 
00010 #include <ros.h>
00011 #include <geometry_msgs/Twist.h>
00012 #include <nav_msgs/Odometry.h>
00013 
00014 
00015 /*
00016 * Joystick has analog out of 200-700, scale values between 1.3 and 3.3
00017 */             
00018 #define def (2.5f/3.3f)                 //Default axis on joystick to stay neutral; used on x and y axis
00019 #define high 3.3f/3.3f                  //High power on joystick; used on x and y axis
00020 #define low (1.7f/3.3f)                 //Low power on joystick; used on x and y axis
00021 #define offset .035f                    //Joystick adjustment to be able to go straight. Chair dependent on manufactoring precision
00022 #define process .1                      //Defines default time delay in seconds
00023 
00024 /* Pin plug in for Nucleo-L432KC */
00025 #define xDir PA_6                         //* PWM Pins */
00026 #define yDir PA_5
00027 #define Encoder1 D7                     //*Digital In Pull Up Pin */
00028 #define Encoder2 D8
00029 #define Diameter 31.75                  //Diameter of encoder wheel
00030 #define maxDeceleration 130
00031 
00032 #define ToFSensorNum 12
00033 
00034 
00035 /** Wheelchair class
00036  * Used for controlling the smart wheelchair
00037  */
00038 
00039 class Wheelchair
00040 {
00041 public:
00042     /** Create Wheelchair Object with x,y pin for analog dc output
00043      * serial for printout, and timer
00044      */
00045     Wheelchair(PinName xPin, PinName yPin, Serial* pc, Timer* time, QEI* wheel, QEI* wheelS,
00046      VL53L1X** ToF);
00047     
00048     /** Move using the joystick */
00049     void move(float x_coor, float y_coor);
00050     
00051     /* Turn right a certain amount of degrees using PID*/
00052     void pid_right(int deg);
00053     
00054     /* Turn left a certain amount of degrees using PID*/
00055     void pid_left(int deg);
00056     
00057     /* Drive the wheelchair forward */
00058     void forward();
00059     
00060     /* Drive the wheelchair in reverse*/
00061     void backward();
00062     
00063     /* Turn the wheelchair right*/
00064     void right();
00065     
00066     /* Turn the wheelchair left*/
00067     void left();
00068     
00069     /* Stop the wheelchair*/
00070     void stop();
00071     
00072     /* Functions to get IMU data*/
00073     void compass_thread();
00074     void velocity_thread();
00075     void rosCom_thread();
00076     void assistSafe_thread();
00077     
00078     void emergencyButton_thread();
00079 
00080     
00081     /* Move x millimiters foward using PID*/
00082     void pid_forward(double mm);
00083     
00084     /* Obtain angular position for Twist message */
00085     double getTwistZ();
00086     
00087     /*  Gets the encoder distance moved since encoder reset*/
00088     float getDistance();
00089     
00090     /* Resets encoder*/
00091     void resetDistance();
00092     
00093     /* Function to determine whether we are turning left or right*/
00094     void pid_turn(int deg);
00095     
00096     /* Function to obtain angular and linear velocity */
00097     void pid_twistA();
00098     void pid_twistV();
00099     
00100     /* Function to publish and show Odometry message */
00101     void odomMsg();
00102     void showOdom();
00103     
00104     /* Functions with a predetermined path (demo) */
00105     void desk();
00106     void kitchen();
00107     void desk_to_kitchen();
00108     
00109     /* Variables for postion, angle, and velocity */
00110     double x_position;
00111     double y_position;
00112     double z_angular;   
00113     double curr_vel;
00114     double z_twistA;
00115     double linearV;
00116     double angularV;
00117     double vel;
00118     double test1, test2;  
00119     bool forwardSafety;
00120     double curr_yaw, curr_velS;                                                            // Variable that contains current relative angle
00121 
00122     
00123 private:
00124     /* Pointers for the joystick speed */
00125     PwmOut* x;
00126     PwmOut* y;
00127     
00128     chair_BNO055* imu;                  // Pointer to IMU
00129     Serial* out;                        // Pointer to Serial Monitor
00130     Timer* ti;                          // Pointer to the timer
00131     QEI* wheel;                         // Pointer to encoder
00132     QEI* wheelS;                        // Pointer to encoder
00133     VL53L1X** ToF;                      // Arrays of pointers to ToF sensors
00134 
00135     
00136 };
00137 #endif