for ros integration
Dependencies: wheelchaircontrolRos
Fork of wheelchaircontrolrealtime by
main.cpp@6:b8a1fa98707e, 2018-08-15 (annotated)
- Committer:
- ryanlin97
- Date:
- Wed Aug 15 17:05:59 2018 +0000
- Revision:
- 6:b8a1fa98707e
- Parent:
- 5:186967c92ef5
- Child:
- 7:cead0e7b0c1e
turning on and off;
Who changed what in which revision?
User | Revision | Line number | New 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 | 6:b8a1fa98707e | 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 | 6:b8a1fa98707e | 47 | on = 0; |
ryanlin97 | 6:b8a1fa98707e | 48 | off = 0; |
ryanlin97 | 6:b8a1fa98707e | 49 | |
ryanlin97 | 0:7e6b349182bc | 50 | queue.call_every(SAMPLEFREQ, &smart, &Wheelchair::compass_thread); |
ryanlin97 | 0:7e6b349182bc | 51 | t.reset(); |
ryanlin97 | 0:7e6b349182bc | 52 | thread.start(callback(&queue, &EventQueue::dispatch_forever)); |
ryanlin97 | 3:ef063fd4234e | 53 | setupNode(); |
ryanlin97 | 6:b8a1fa98707e | 54 | while(1) { |
ryanlin97 | 5:186967c92ef5 | 55 | if( received) { |
ryanlin97 | 0:7e6b349182bc | 56 | |
ryanlin97 | 5:186967c92ef5 | 57 | if( c == 'w') { |
ryanlin97 | 5:186967c92ef5 | 58 | pc.printf("up \n"); |
ryanlin97 | 5:186967c92ef5 | 59 | smart.forward(); |
ryanlin97 | 5:186967c92ef5 | 60 | } |
ryanlin97 | 0:7e6b349182bc | 61 | |
ryanlin97 | 5:186967c92ef5 | 62 | else if( c == 'a') { |
ryanlin97 | 5:186967c92ef5 | 63 | //pc.printf("left \n"); |
ryanlin97 | 5:186967c92ef5 | 64 | smart.left(); |
ryanlin97 | 5:186967c92ef5 | 65 | } |
ryanlin97 | 0:7e6b349182bc | 66 | |
ryanlin97 | 5:186967c92ef5 | 67 | else if( c == 'd') { |
ryanlin97 | 5:186967c92ef5 | 68 | //pc.printf("right \n"); |
ryanlin97 | 5:186967c92ef5 | 69 | smart.right(); |
ryanlin97 | 5:186967c92ef5 | 70 | } |
ryanlin97 | 0:7e6b349182bc | 71 | |
ryanlin97 | 5:186967c92ef5 | 72 | else if( c == 's') { |
ryanlin97 | 5:186967c92ef5 | 73 | pc.printf("down \n"); |
ryanlin97 | 5:186967c92ef5 | 74 | smart.backward(); |
ryanlin97 | 5:186967c92ef5 | 75 | } |
ryanlin97 | 0:7e6b349182bc | 76 | |
ryanlin97 | 5:186967c92ef5 | 77 | else if( c == 'r') { |
ryanlin97 | 5:186967c92ef5 | 78 | smart.turn_right(90); |
ryanlin97 | 5:186967c92ef5 | 79 | } |
ryanlin97 | 0:7e6b349182bc | 80 | |
ryanlin97 | 5:186967c92ef5 | 81 | else if( c == 'l') { |
ryanlin97 | 5:186967c92ef5 | 82 | smart.turn_left(90); |
ryanlin97 | 0:7e6b349182bc | 83 | } |
ryanlin97 | 0:7e6b349182bc | 84 | |
ryanlin97 | 5:186967c92ef5 | 85 | else if( c == 't') { |
ryanlin97 | 5:186967c92ef5 | 86 | char buffer[256]; |
ryanlin97 | 5:186967c92ef5 | 87 | pc.printf ("Enter a long number: "); |
ryanlin97 | 5:186967c92ef5 | 88 | fgets (buffer, 256, stdin); |
ryanlin97 | 5:186967c92ef5 | 89 | int angle = atoi (buffer); |
ryanlin97 | 5:186967c92ef5 | 90 | |
ryanlin97 | 5:186967c92ef5 | 91 | if(angle == 0) { |
ryanlin97 | 5:186967c92ef5 | 92 | pc.printf("invalid input try again\n"); |
ryanlin97 | 5:186967c92ef5 | 93 | } else { |
ryanlin97 | 5:186967c92ef5 | 94 | smart.pid_turn(angle); |
ryanlin97 | 5:186967c92ef5 | 95 | } |
ryanlin97 | 0:7e6b349182bc | 96 | |
ryanlin97 | 6:b8a1fa98707e | 97 | } else if(c == 'o') { |
ryanlin97 | 6:b8a1fa98707e | 98 | pc.printf("turning on\n"); |
ryanlin97 | 6:b8a1fa98707e | 99 | on = 1; |
ryanlin97 | 6:b8a1fa98707e | 100 | wait(1); |
ryanlin97 | 6:b8a1fa98707e | 101 | on = 0; |
ryanlin97 | 6:b8a1fa98707e | 102 | } else if(c == 'f') { |
ryanlin97 | 6:b8a1fa98707e | 103 | pc.printf("turning off\n"); |
ryanlin97 | 6:b8a1fa98707e | 104 | off = 1; |
ryanlin97 | 6:b8a1fa98707e | 105 | wait(1); |
ryanlin97 | 6:b8a1fa98707e | 106 | off = 0; |
ryanlin97 | 5:186967c92ef5 | 107 | } |
ryanlin97 | 5:186967c92ef5 | 108 | |
ryanlin97 | 5:186967c92ef5 | 109 | else if( c == 'm' || manual) { |
ryanlin97 | 5:186967c92ef5 | 110 | pc.printf("turning on joystick\n"); |
ryanlin97 | 5:186967c92ef5 | 111 | manual = true; |
ryanlin97 | 5:186967c92ef5 | 112 | t.reset(); |
ryanlin97 | 5:186967c92ef5 | 113 | while(manual) { |
ryanlin97 | 5:186967c92ef5 | 114 | smart.move(x,y); |
ryanlin97 | 5:186967c92ef5 | 115 | if( pc.readable()) { |
ryanlin97 | 5:186967c92ef5 | 116 | char d = pc.getc(); |
ryanlin97 | 5:186967c92ef5 | 117 | if( d == 'm') { |
ryanlin97 | 5:186967c92ef5 | 118 | pc.printf("turning off joystick\n"); |
ryanlin97 | 5:186967c92ef5 | 119 | manual = false; |
ryanlin97 | 5:186967c92ef5 | 120 | } |
ryanlin97 | 0:7e6b349182bc | 121 | } |
ryanlin97 | 0:7e6b349182bc | 122 | } |
ryanlin97 | 0:7e6b349182bc | 123 | } |
ryanlin97 | 5:186967c92ef5 | 124 | |
ryanlin97 | 5:186967c92ef5 | 125 | else { |
ryanlin97 | 5:186967c92ef5 | 126 | pc.printf("none \n"); |
ryanlin97 | 5:186967c92ef5 | 127 | smart.stop(); |
ryanlin97 | 5:186967c92ef5 | 128 | } |
ryanlin97 | 0:7e6b349182bc | 129 | } |
ryanlin97 | 0:7e6b349182bc | 130 | |
ryanlin97 | 0:7e6b349182bc | 131 | else { |
ryanlin97 | 5:186967c92ef5 | 132 | // pc.printf("Nothing pressed \n"); |
ryanlin97 | 0:7e6b349182bc | 133 | smart.stop(); |
ryanlin97 | 0:7e6b349182bc | 134 | } |
ryanlin97 | 0:7e6b349182bc | 135 | wait(process); |
ryanlin97 | 0:7e6b349182bc | 136 | } |
ryanlin97 | 0:7e6b349182bc | 137 | |
ryanlin97 | 0:7e6b349182bc | 138 | } |
ryanlin97 | 0:7e6b349182bc | 139 | |
ryanlin97 | 3:ef063fd4234e | 140 | |
ryanlin97 | 3:ef063fd4234e | 141 | |
ryanlin97 | 3:ef063fd4234e | 142 | |
ryanlin97 | 3:ef063fd4234e | 143 | |
ryanlin97 | 3:ef063fd4234e | 144 | |
ryanlin97 | 3:ef063fd4234e | 145 | |
ryanlin97 | 3:ef063fd4234e | 146 |