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