1

Dependencies:   QEI2 chair_BNO055 PID Watchdog VL53L1X_Filter ros_lib_kinetic

Dependents:   wheelchairControlSumer2019

Committer:
jvfausto
Date:
Tue Aug 28 23:24:08 2018 +0000
Revision:
17:7f3b69300bb6
Parent:
16:b403082eeacd
Child:
19:71a6621ee5c3
with pid left, right and foward

Who changed what in which revision?

UserRevisionLine numberNew contents of line
ryanlin97 0:fc0c4a184482 1 #ifndef wheelchair
ryanlin97 0:fc0c4a184482 2 #define wheelchair
ryanlin97 0:fc0c4a184482 3
ryanlin97 11:d14a1f7f1297 4 #include "chair_BNO055.h"
jvfausto 17:7f3b69300bb6 5 #include "PID.h"
ryanlin97 12:921488918749 6 #include "QEI.h"
ryanlin97 16:b403082eeacd 7 #include <ros.h>
ryanlin97 16:b403082eeacd 8 #include <geometry_msgs/Twist.h>
jvfausto 17:7f3b69300bb6 9 //#include "BufferedSerial.h"
ryanlin97 12:921488918749 10
ryanlin97 11:d14a1f7f1297 11 //#include "chair_MPU9250.h"
ryanlin97 0:fc0c4a184482 12
ryanlin97 11:d14a1f7f1297 13 #define turn_precision 10
ryanlin97 0:fc0c4a184482 14 #define def (2.5f/3.3f)
ryanlin97 12:921488918749 15 #define high 3.3f/3.3f
ryanlin97 3:a5e71bfdb492 16 #define offset .02f
ryanlin97 3:a5e71bfdb492 17 #define low (1.7f/3.3f)
ryanlin97 10:e5463c11e0a0 18 #define process .1
ryanlin97 14:9caca9fde9b0 19
ryanlin97 14:9caca9fde9b0 20 /* for big mbed board
ryanlin97 3:a5e71bfdb492 21 #define xDir D12 //top right two pins
ryanlin97 0:fc0c4a184482 22 #define yDir D13 //top left two pins
ryanlin97 12:921488918749 23 #define Encoder1 D0
ryanlin97 12:921488918749 24 #define Encoder2 D1
ryanlin97 14:9caca9fde9b0 25 */
ryanlin97 14:9caca9fde9b0 26
ryanlin97 14:9caca9fde9b0 27 //for small mbed board
ryanlin97 14:9caca9fde9b0 28 #define xDir D9
ryanlin97 14:9caca9fde9b0 29 #define yDir D10
ryanlin97 14:9caca9fde9b0 30 #define Encoder1 D7
ryanlin97 14:9caca9fde9b0 31 #define Encoder2 D8
ryanlin97 14:9caca9fde9b0 32
ryanlin97 12:921488918749 33 #define EncoderReadRate 1200
ryanlin97 12:921488918749 34 #define Diameter 31.75
ryanlin97 12:921488918749 35 /** Wheelchair class
ryanlin97 12:921488918749 36 * Used for controlling the smart wheelchair
ryanlin97 12:921488918749 37 */
jvfausto 17:7f3b69300bb6 38
ryanlin97 0:fc0c4a184482 39 class Wheelchair
ryanlin97 0:fc0c4a184482 40 {
ryanlin97 0:fc0c4a184482 41 public:
ryanlin97 12:921488918749 42 /** Create Wheelchair Object with x,y pin for analog dc output
ryanlin97 12:921488918749 43 * serial for printout, and timer
ryanlin97 12:921488918749 44 */
ryanlin97 7:5e38d43fbce3 45 Wheelchair(PinName xPin, PinName yPin, Serial* pc, Timer* time);
ryanlin97 12:921488918749 46
ryanlin97 12:921488918749 47 /** move using the joystick */
ryanlin97 3:a5e71bfdb492 48 void move(float x_coor, float y_coor);
ryanlin97 12:921488918749 49
ryanlin97 12:921488918749 50 /* turn right a certain amount of degrees (overshoots)*/
ryanlin97 11:d14a1f7f1297 51 double turn_right(int deg);
ryanlin97 12:921488918749 52
ryanlin97 12:921488918749 53 /* turn left a certain amount of degrees (overshoots)*/
ryanlin97 11:d14a1f7f1297 54 double turn_left(int deg);
ryanlin97 12:921488918749 55
ryanlin97 12:921488918749 56 /* turn right a certain amount of degrees using PID*/
ryanlin97 12:921488918749 57 void pid_right(int deg);
ryanlin97 12:921488918749 58
ryanlin97 12:921488918749 59 /* turn left a certain amount of degrees using PID*/
ryanlin97 12:921488918749 60 void pid_left(int deg);
ryanlin97 12:921488918749 61
ryanlin97 12:921488918749 62 /* turning function that turns any direction */
ryanlin97 11:d14a1f7f1297 63 void turn(int deg);
ryanlin97 12:921488918749 64
ryanlin97 12:921488918749 65 /* drive the wheelchair forward */
ryanlin97 1:c0beadca1617 66 void forward();
ryanlin97 12:921488918749 67
ryanlin97 12:921488918749 68 /* drive the wheelchair backward*/
ryanlin97 1:c0beadca1617 69 void backward();
ryanlin97 12:921488918749 70
ryanlin97 12:921488918749 71 /* turn the wheelchair right*/
ryanlin97 1:c0beadca1617 72 void right();
ryanlin97 12:921488918749 73
ryanlin97 12:921488918749 74 /* turn the wheelchair left*/
ryanlin97 1:c0beadca1617 75 void left();
ryanlin97 12:921488918749 76
ryanlin97 12:921488918749 77 /* stop the wheelchair*/
ryanlin97 1:c0beadca1617 78 void stop();
ryanlin97 12:921488918749 79
ryanlin97 12:921488918749 80 /* function to get imu data*/
ryanlin97 11:d14a1f7f1297 81 void compass_thread();
jvfausto 17:7f3b69300bb6 82 void distance_thread();
jvfausto 17:7f3b69300bb6 83 void pid_foward(double mm);
jvfausto 17:7f3b69300bb6 84 void pid_reverse(double mm);
ryanlin97 12:921488918749 85 float getDistance();
ryanlin97 12:921488918749 86 void resetDistance();
ryanlin97 12:921488918749 87 void pid_turn(int deg);
ryanlin97 12:921488918749 88
ryanlin97 1:c0beadca1617 89 private:
ryanlin97 3:a5e71bfdb492 90 PwmOut* x;
ryanlin97 3:a5e71bfdb492 91 PwmOut* y;
ryanlin97 12:921488918749 92 chair_BNO055* imu;
ryanlin97 7:5e38d43fbce3 93 Serial* out;
jvfausto 17:7f3b69300bb6 94 Timer* tim;
ryanlin97 11:d14a1f7f1297 95 Timer* ti;
ryanlin97 12:921488918749 96 QEI* wheel;
ryanlin97 1:c0beadca1617 97
ryanlin97 0:fc0c4a184482 98 };
ryanlin97 0:fc0c4a184482 99 #endif