Working file for communication with ROS
Dependencies: QEI2 PID VL53L1X_Filter
Diff: wheelchair.h
- Revision:
- 23:8d11d953ceeb
- Parent:
- 20:f42db4ae16f0
- Child:
- 24:d2f234fbc20d
--- a/wheelchair.h Fri Aug 31 20:00:01 2018 +0000 +++ b/wheelchair.h Tue Oct 16 23:03:40 2018 +0000 @@ -1,37 +1,30 @@ #ifndef wheelchair #define wheelchair +//Importing libraries into wheelchair.h #include "chair_BNO055.h" #include "PID.h" #include "QEI.h" #include <ros.h> #include <geometry_msgs/Twist.h> -//#include "BufferedSerial.h" -//#include "chair_MPU9250.h" - -#define turn_precision 10 -#define def (2.5f/3.3f) -#define high 3.3f/3.3f -#define offset .02742f -#define low (1.7f/3.3f) -#define process .1 -/* for big mbed board -#define xDir D12 //top right two pins -#define yDir D13 //top left two pins -#define Encoder1 D0 -#define Encoder2 D1 -*/ +/* +* joystick has analog out of 200-700, scale values between 1.3 and 3.3 +*/ +#define def (2.5f/3.3f) //Default axis on joystick to stay neutral; used on x and y axis +#define high 3.3f/3.3f //High power on joystick; used on x and y axis +#define low (1.7f/3.3f) //Low power on joystick; used on x and y axis +#define offset .035f //Joystick ajustment to be able to go strait. Chair dependent on manufactoring presision +#define process .1 //Defines default time delay in seconds -//for small mbed board -#define xDir D9 +//Pin plug in for Nucleo-L432KC +#define xDir D9 //PWM Pins #define yDir D10 -#define Encoder1 D7 +#define Encoder1 D7 //Digital In Pull Up Pin #define Encoder2 D8 -#define EncoderReadRate 1200 -#define Diameter 31.75 +#define Diameter 31.75 //Diameter of encoder wheel /** Wheelchair class * Used for controlling the smart wheelchair */ @@ -47,21 +40,12 @@ /** move using the joystick */ void move(float x_coor, float y_coor); - /* turn right a certain amount of degrees (overshoots)*/ - double turn_right(int deg); - - /* turn left a certain amount of degrees (overshoots)*/ - double turn_left(int deg); - /* turn right a certain amount of degrees using PID*/ void pid_right(int deg); /* turn left a certain amount of degrees using PID*/ void pid_left(int deg); - /* turning function that turns any direction */ - void turn(int deg); - /* drive the wheelchair forward */ void forward(); @@ -79,23 +63,35 @@ /* function to get imu data*/ void compass_thread(); - void distance_thread(); + + /* move x millimiters foward using PID*/ void pid_forward(double mm); + + /* move x millimiters reverse using PID*/ void pid_reverse(double mm); + + /* gets the encoder distance moved since encoder reset*/ float getDistance(); + + /* resets encoder*/ void resetDistance(); + + /* function to to determine whether we are turning left or right*/ void pid_turn(int deg); + + /* functions with a predetermined path demmo*/ void desk(); void kitchen(); void desk_to_kitchen(); private: + /* Pointers for the joystick speed*/ PwmOut* x; PwmOut* y; - chair_BNO055* imu; - Serial* out; - Timer* tim; - Timer* ti; - QEI* wheel; + + chair_BNO055* imu; // Pointer to IMU + Serial* out; // Pointer to Serial Monitor + Timer* ti; // Pointer to the timer + QEI* wheel; // Pointer to encoder }; #endif \ No newline at end of file