for ros
Dependencies: QEI chair_BNO055 pid ros_lib_kinetic
Dependents: wheelchaircontrolrealtimeROS
Fork of wheelchaircontrol by
wheelchair.h
00001 #ifndef wheelchair 00002 #define wheelchair 00003 00004 #include "chair_BNO055.h" 00005 #include "PID_v1.h" 00006 #include "QEI.h" 00007 #include <ros.h> 00008 #include <geometry_msgs/Twist.h> 00009 #include <std_msgs/String.h> 00010 #include <string> 00011 00012 #define turn_precision 10 00013 #define def (2.5f/3.3f) 00014 #define high (3.3f-.15f)/3.3f 00015 #define offset .02742f 00016 #define low (1.7f/3.3f) 00017 #define process .1 00018 00019 /* for big mbed board 00020 #define xDir D12 //top right two pins 00021 #define yDir D13 //top left two pins 00022 #define Encoder1 D0 00023 #define Encoder2 D1 00024 */ 00025 00026 //for small mbed board 00027 #define xDir D9 00028 #define yDir D10 00029 #define Encoder1 D7 00030 #define Encoder2 D8 00031 00032 #define EncoderReadRate 1200 00033 #define Diameter 31.75 00034 /** Wheelchair class 00035 * Used for controlling the smart wheelchair 00036 */ 00037 class Wheelchair 00038 { 00039 public: 00040 /** Create Wheelchair Object with x,y pin for analog dc output 00041 * serial for printout, and timer 00042 */ 00043 Wheelchair(PinName xPin, PinName yPin, Serial* pc, Timer* time, QEI* qei); 00044 00045 /** move using the joystick */ 00046 void move(float x_coor, float y_coor); 00047 00048 /* turn right a certain amount of degrees (overshoots)*/ 00049 double turn_right(int deg); 00050 00051 /* turn left a certain amount of degrees (overshoots)*/ 00052 double turn_left(int deg); 00053 00054 /* turn right a certain amount of degrees using PID*/ 00055 void pid_right(int deg); 00056 00057 /* turn left a certain amount of degrees using PID*/ 00058 void pid_left(int deg); 00059 00060 /* turning function that turns any direction */ 00061 void turn(int deg); 00062 00063 /* drive the wheelchair forward */ 00064 void forward(); 00065 00066 /* drive the wheelchair backward*/ 00067 void backward(); 00068 00069 /* turn the wheelchair right*/ 00070 void right(); 00071 00072 /* turn the wheelchair left*/ 00073 void left(); 00074 00075 /* stop the wheelchair*/ 00076 void stop(); 00077 00078 /* function to get imu data*/ 00079 void compass_thread(); 00080 float getDistance(); 00081 void resetDistance(); 00082 void pid_turn(int deg); 00083 void turn_on(); 00084 void turn_off(); 00085 void pid_forward(double mm); 00086 void kitchen(); 00087 void desk(); 00088 void follow(); 00089 void back(); 00090 00091 private: 00092 double readEncoder(); 00093 PwmOut* x; 00094 PwmOut* y; 00095 chair_BNO055* imu; 00096 Serial* out; 00097 Timer* ti; 00098 QEI* wheel; 00099 00100 00101 }; 00102 #endif
Generated on Thu Jul 14 2022 09:19:28 by 1.7.2