Jesus Fausto / wheelchaircontrol

Dependencies:   PID QEI chair_BNO055 ros_lib_kinetic

Dependents:  

Fork of wheelchaircontrol by ryan lin

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 <ros.h>
00009 #include <geometry_msgs/Twist.h>
00010 
00011 
00012 /*
00013 * joystick has analog out of 200-700, scale values between 1.3 and 3.3
00014 */             
00015 #define def (2.5f/3.3f)                 //Default axis on joystick to stay neutral; used on x and y axis
00016 #define high 3.3f/3.3f                  //High power on joystick; used on x and y axis
00017 #define low (1.7f/3.3f)                 //Low power on joystick; used on x and y axis
00018 #define offset .035f                  //Joystick ajustment to be able to go strait. Chair dependent on manufactoring presision
00019 #define process .1                      //Defines default time delay in seconds
00020 
00021 //Pin plug in for Nucleo-L432KC
00022 #define xDir D9                         //PWM Pins
00023 #define yDir D10
00024 #define Encoder1 D7                     //Digital In Pull Up Pin
00025 #define Encoder2 D8
00026 
00027 #define Diameter 31.75                  //Diameter of encoder wheel
00028 /** Wheelchair class
00029  * Used for controlling the smart wheelchair
00030  */
00031 
00032 class Wheelchair
00033 {
00034 public:
00035     /** Create Wheelchair Object with x,y pin for analog dc output
00036      * serial for printout, and timer
00037      */
00038     Wheelchair(PinName xPin, PinName yPin, Serial* pc, Timer* time, QEI* wheel, QEI* wheelS);
00039     
00040     /** move using the joystick */
00041     void move(float x_coor, float y_coor);
00042     
00043     /* turn right a certain amount of degrees using PID*/
00044     void pid_right(int deg);
00045     
00046     /* turn left a certain amount of degrees using PID*/
00047     void pid_left(int deg);
00048     
00049     /* drive the wheelchair forward */
00050     void forward();
00051     
00052     /* drive the wheelchair backward*/
00053     void backward();
00054     
00055     /* turn the wheelchair right*/
00056     void right();
00057     
00058     /* turn the wheelchair left*/
00059     void left();
00060     
00061     /* stop the wheelchair*/
00062     void stop();
00063     
00064     /* function to get imu data*/
00065     void compass_thread();
00066     void velosity_thread();
00067     
00068     /* move x millimiters foward using PID*/
00069     void pid_forward(double mm);
00070     
00071     /* move x millimiters reverse using PID*/
00072     void pid_reverse(double mm);
00073     
00074     /*  gets the encoder distance moved since encoder reset*/
00075     float getDistance();
00076     
00077     /* resets encoder*/
00078     void resetDistance();
00079     
00080     /* function to to determine whether we are turning left or right*/
00081     void pid_turn(int deg);
00082     
00083     void pid_twistA();
00084     void pid_twistV();
00085     
00086     void odomMsg();
00087     void showOdom();
00088     
00089     /* functions with a predetermined path demmo*/
00090     void desk();
00091     void kitchen();
00092     void desk_to_kitchen();
00093     
00094 private:
00095     /* Pointers for the joystick speed*/
00096     PwmOut* x;
00097     PwmOut* y;
00098     
00099     chair_BNO055* imu;                  // Pointer to IMU
00100     Serial* out;                        // Pointer to Serial Monitor
00101     Timer* ti;                          // Pointer to the timer
00102     QEI* wheel;                         // Pointer to encoder
00103     QEI* wheelS;                         // Pointer to encoder
00104 };
00105 #endif