Summer 19 code

Dependencies:   wheelchaircontrol1

Committer:
ryanlin97
Date:
Mon Aug 13 21:43:02 2018 +0000
Revision:
4:db3aa99ab312
Parent:
3:ef063fd4234e
fixed;

Who changed what in which revision?

UserRevisionLine numberNew contents of line
ryanlin97 0:7e6b349182bc 1 #include "wheelchair.h"
ryanlin97 0:7e6b349182bc 2
ryanlin97 0:7e6b349182bc 3 AnalogIn x(A0);
ryanlin97 0:7e6b349182bc 4 AnalogIn y(A1);
ryanlin97 0:7e6b349182bc 5
ryanlin97 0:7e6b349182bc 6 DigitalOut off(D0);
ryanlin97 0:7e6b349182bc 7 DigitalOut on(D1);
ryanlin97 0:7e6b349182bc 8 DigitalOut up(D2);
ryanlin97 0:7e6b349182bc 9 DigitalOut down(D3);
ryanlin97 0:7e6b349182bc 10
ryanlin97 3:ef063fd4234e 11 char c;
ryanlin97 0:7e6b349182bc 12 bool manual = false;
ryanlin97 3:ef063fd4234e 13 bool received = false;
ryanlin97 3:ef063fd4234e 14 Serial pc(USBTX, USBRX, 57600);
ryanlin97 0:7e6b349182bc 15
ryanlin97 0:7e6b349182bc 16 Timer t;
ryanlin97 0:7e6b349182bc 17 EventQueue queue;
ryanlin97 0:7e6b349182bc 18
ryanlin97 0:7e6b349182bc 19 //MPU9250 imu(D14, D15);
ryanlin97 0:7e6b349182bc 20 Wheelchair smart(xDir,yDir, &pc, &t);
ryanlin97 0:7e6b349182bc 21 Thread thread;
ryanlin97 0:7e6b349182bc 22
ryanlin97 3:ef063fd4234e 23 ros::NodeHandle nh;
ryanlin97 3:ef063fd4234e 24 geometry_msgs::Twist commandRead;
ryanlin97 3:ef063fd4234e 25 ros::Publisher chatter("chatter", &commandRead);
ryanlin97 3:ef063fd4234e 26
ryanlin97 3:ef063fd4234e 27 void handlerFunction(const geometry_msgs::Twist& command)
ryanlin97 3:ef063fd4234e 28 {
ryanlin97 3:ef063fd4234e 29 if(command.linear.x >0) {
ryanlin97 4:db3aa99ab312 30 c = 'w';
ryanlin97 3:ef063fd4234e 31 }
ryanlin97 3:ef063fd4234e 32 received = true;
ryanlin97 3:ef063fd4234e 33 }
ryanlin97 3:ef063fd4234e 34
ryanlin97 3:ef063fd4234e 35 ros::Subscriber<geometry_msgs::Twist> sub("cmd_vel", &handlerFunction);
ryanlin97 3:ef063fd4234e 36
ryanlin97 3:ef063fd4234e 37
ryanlin97 3:ef063fd4234e 38 void setupNode()
ryanlin97 3:ef063fd4234e 39 {
ryanlin97 3:ef063fd4234e 40 nh.initNode();
ryanlin97 3:ef063fd4234e 41 nh.subscribe(sub);
ryanlin97 3:ef063fd4234e 42 nh.advertise(chatter);
ryanlin97 3:ef063fd4234e 43 }
ryanlin97 3:ef063fd4234e 44
ryanlin97 0:7e6b349182bc 45 int main(void)
ryanlin97 0:7e6b349182bc 46 {
ryanlin97 0:7e6b349182bc 47 queue.call_every(SAMPLEFREQ, &smart, &Wheelchair::compass_thread);
ryanlin97 0:7e6b349182bc 48 t.reset();
ryanlin97 0:7e6b349182bc 49 thread.start(callback(&queue, &EventQueue::dispatch_forever));
ryanlin97 3:ef063fd4234e 50 setupNode();
ryanlin97 3:ef063fd4234e 51 if(received) {
ryanlin97 3:ef063fd4234e 52
ryanlin97 3:ef063fd4234e 53 if( c == 'w') {
ryanlin97 3:ef063fd4234e 54 pc.printf("up \n");
ryanlin97 3:ef063fd4234e 55 smart.forward();
ryanlin97 3:ef063fd4234e 56 }
ryanlin97 0:7e6b349182bc 57
ryanlin97 3:ef063fd4234e 58 else if( c == 'a') {
ryanlin97 3:ef063fd4234e 59 //pc.printf("left \n");
ryanlin97 3:ef063fd4234e 60 smart.left();
ryanlin97 3:ef063fd4234e 61 }
ryanlin97 0:7e6b349182bc 62
ryanlin97 3:ef063fd4234e 63 else if( c == 'd') {
ryanlin97 3:ef063fd4234e 64 //pc.printf("right \n");
ryanlin97 3:ef063fd4234e 65 smart.right();
ryanlin97 3:ef063fd4234e 66 }
ryanlin97 0:7e6b349182bc 67
ryanlin97 3:ef063fd4234e 68 else if( c == 's') {
ryanlin97 3:ef063fd4234e 69 pc.printf("down \n");
ryanlin97 3:ef063fd4234e 70 smart.backward();
ryanlin97 3:ef063fd4234e 71 }
ryanlin97 3:ef063fd4234e 72
ryanlin97 3:ef063fd4234e 73 else if( c == 'r') {
ryanlin97 3:ef063fd4234e 74 smart.turn_right(90);
ryanlin97 3:ef063fd4234e 75 }
ryanlin97 0:7e6b349182bc 76
ryanlin97 3:ef063fd4234e 77 else if( c == 'l') {
ryanlin97 3:ef063fd4234e 78 smart.turn_left(90);
ryanlin97 3:ef063fd4234e 79 }
ryanlin97 0:7e6b349182bc 80
ryanlin97 3:ef063fd4234e 81 else if( c == 't') {
ryanlin97 3:ef063fd4234e 82 char buffer[256];
ryanlin97 3:ef063fd4234e 83 pc.printf ("Enter a long number: ");
ryanlin97 3:ef063fd4234e 84 fgets (buffer, 256, stdin);
ryanlin97 3:ef063fd4234e 85 int angle = atoi (buffer);
ryanlin97 0:7e6b349182bc 86
ryanlin97 3:ef063fd4234e 87 if(angle == 0) {
ryanlin97 3:ef063fd4234e 88 pc.printf("invalid input try again\n");
ryanlin97 3:ef063fd4234e 89 } else {
ryanlin97 3:ef063fd4234e 90 smart.pid_turn(angle);
ryanlin97 0:7e6b349182bc 91 }
ryanlin97 0:7e6b349182bc 92
ryanlin97 3:ef063fd4234e 93 }
ryanlin97 0:7e6b349182bc 94
ryanlin97 3:ef063fd4234e 95 else if( c == 'm' || manual) {
ryanlin97 3:ef063fd4234e 96 pc.printf("turning on joystick\n");
ryanlin97 3:ef063fd4234e 97 manual = true;
ryanlin97 3:ef063fd4234e 98 t.reset();
ryanlin97 3:ef063fd4234e 99 while(manual) {
ryanlin97 3:ef063fd4234e 100 smart.move(x,y);
ryanlin97 3:ef063fd4234e 101 if( pc.readable()) {
ryanlin97 3:ef063fd4234e 102 char d = pc.getc();
ryanlin97 3:ef063fd4234e 103 if( d == 'm') {
ryanlin97 3:ef063fd4234e 104 pc.printf("turning off joystick\n");
ryanlin97 3:ef063fd4234e 105 manual = false;
ryanlin97 0:7e6b349182bc 106 }
ryanlin97 0:7e6b349182bc 107 }
ryanlin97 0:7e6b349182bc 108 }
ryanlin97 0:7e6b349182bc 109 }
ryanlin97 0:7e6b349182bc 110
ryanlin97 0:7e6b349182bc 111 else {
ryanlin97 3:ef063fd4234e 112 pc.printf("none \n");
ryanlin97 0:7e6b349182bc 113 smart.stop();
ryanlin97 0:7e6b349182bc 114 }
ryanlin97 3:ef063fd4234e 115
ryanlin97 0:7e6b349182bc 116 wait(process);
ryanlin97 3:ef063fd4234e 117 received = !received;
ryanlin97 0:7e6b349182bc 118 }
ryanlin97 0:7e6b349182bc 119
ryanlin97 0:7e6b349182bc 120 }
ryanlin97 0:7e6b349182bc 121
ryanlin97 3:ef063fd4234e 122
ryanlin97 3:ef063fd4234e 123
ryanlin97 3:ef063fd4234e 124 /*
ryanlin97 3:ef063fd4234e 125 void publishTwist(ros::Publisher* toChat) [
ryanlin97 3:ef063fd4234e 126 toChat->publish( &commandRead);
ryanlin97 3:ef063fd4234e 127 nh.spinOnce();
ryanlin97 3:ef063fd4234e 128 }*/
ryanlin97 3:ef063fd4234e 129
ryanlin97 3:ef063fd4234e 130
ryanlin97 3:ef063fd4234e 131
ryanlin97 3:ef063fd4234e 132
ryanlin97 3:ef063fd4234e 133