for ros integration
Dependencies: wheelchaircontrolRos
Fork of wheelchaircontrolrealtime by
main.cpp@9:90bc440405b6, 2018-08-29 (annotated)
- Committer:
- ryanlin97
- Date:
- Wed Aug 29 21:02:03 2018 +0000
- Revision:
- 9:90bc440405b6
- Parent:
- 8:347b10e6bdf8
- Child:
- 11:2cb176f5b345
added paths
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 | 9:90bc440405b6 | 6 | /* |
ryanlin97 | 7:cead0e7b0c1e | 7 | DigitalOut on(D12); |
ryanlin97 | 7:cead0e7b0c1e | 8 | DigitalOut off(D11); |
ryanlin97 | 0:7e6b349182bc | 9 | DigitalOut up(D2); |
ryanlin97 | 9:90bc440405b6 | 10 | DigitalOut down(D3);*/ |
ryanlin97 | 0:7e6b349182bc | 11 | |
ryanlin97 | 7:cead0e7b0c1e | 12 | Serial pc(USBTX, USBRX, 57600); |
ryanlin97 | 7:cead0e7b0c1e | 13 | Timer t; |
ryanlin97 | 7:cead0e7b0c1e | 14 | Thread thread; |
ryanlin97 | 7:cead0e7b0c1e | 15 | EventQueue queue; |
ryanlin97 | 7:cead0e7b0c1e | 16 | Wheelchair smart(xDir,yDir, &pc, &t); |
ryanlin97 | 7:cead0e7b0c1e | 17 | |
ryanlin97 | 3:ef063fd4234e | 18 | char c; |
ryanlin97 | 0:7e6b349182bc | 19 | bool manual = false; |
ryanlin97 | 0:7e6b349182bc | 20 | |
ryanlin97 | 3:ef063fd4234e | 21 | ros::NodeHandle nh; |
ryanlin97 | 7:cead0e7b0c1e | 22 | //geometry_msgs::Twist commandRead; |
ryanlin97 | 7:cead0e7b0c1e | 23 | std_msgs::String commandRead; |
ryanlin97 | 3:ef063fd4234e | 24 | |
ryanlin97 | 7:cead0e7b0c1e | 25 | ros::Publisher chatter("chatter", &commandRead); |
ryanlin97 | 9:90bc440405b6 | 26 | volatile bool received = false; |
ryanlin97 | 7:cead0e7b0c1e | 27 | |
ryanlin97 | 7:cead0e7b0c1e | 28 | void handlerFunction(const std_msgs::String& commandIn) |
ryanlin97 | 3:ef063fd4234e | 29 | { |
ryanlin97 | 7:cead0e7b0c1e | 30 | commandRead = commandIn; |
ryanlin97 | 3:ef063fd4234e | 31 | received = true; |
ryanlin97 | 3:ef063fd4234e | 32 | } |
ryanlin97 | 3:ef063fd4234e | 33 | |
ryanlin97 | 7:cead0e7b0c1e | 34 | ros::Subscriber<std_msgs::String> sub("cmd_vel", &handlerFunction); |
ryanlin97 | 3:ef063fd4234e | 35 | |
ryanlin97 | 3:ef063fd4234e | 36 | |
ryanlin97 | 3:ef063fd4234e | 37 | void setupNode() |
ryanlin97 | 3:ef063fd4234e | 38 | { |
ryanlin97 | 3:ef063fd4234e | 39 | nh.initNode(); |
ryanlin97 | 3:ef063fd4234e | 40 | nh.subscribe(sub); |
ryanlin97 | 3:ef063fd4234e | 41 | nh.advertise(chatter); |
ryanlin97 | 7:cead0e7b0c1e | 42 | char initialVal[2] = "z"; |
ryanlin97 | 7:cead0e7b0c1e | 43 | commandRead.data = initialVal; |
ryanlin97 | 3:ef063fd4234e | 44 | } |
ryanlin97 | 3:ef063fd4234e | 45 | |
ryanlin97 | 0:7e6b349182bc | 46 | int main(void) |
ryanlin97 | 0:7e6b349182bc | 47 | { |
ryanlin97 | 6:b8a1fa98707e | 48 | |
ryanlin97 | 0:7e6b349182bc | 49 | queue.call_every(SAMPLEFREQ, &smart, &Wheelchair::compass_thread); |
ryanlin97 | 0:7e6b349182bc | 50 | t.reset(); |
ryanlin97 | 0:7e6b349182bc | 51 | thread.start(callback(&queue, &EventQueue::dispatch_forever)); |
ryanlin97 | 3:ef063fd4234e | 52 | setupNode(); |
ryanlin97 | 7:cead0e7b0c1e | 53 | |
ryanlin97 | 6:b8a1fa98707e | 54 | while(1) { |
ryanlin97 | 5:186967c92ef5 | 55 | if( received) { |
ryanlin97 | 7:cead0e7b0c1e | 56 | c = commandRead.data[0]; |
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 | 7:cead0e7b0c1e | 78 | smart.pid_right(90); |
ryanlin97 | 8:347b10e6bdf8 | 79 | c = 'z'; |
ryanlin97 | 5:186967c92ef5 | 80 | } |
ryanlin97 | 0:7e6b349182bc | 81 | |
ryanlin97 | 5:186967c92ef5 | 82 | else if( c == 'l') { |
ryanlin97 | 7:cead0e7b0c1e | 83 | smart.pid_left(90); |
ryanlin97 | 8:347b10e6bdf8 | 84 | c = 'z'; |
ryanlin97 | 0:7e6b349182bc | 85 | } |
ryanlin97 | 0:7e6b349182bc | 86 | |
ryanlin97 | 5:186967c92ef5 | 87 | else if( c == 't') { |
ryanlin97 | 5:186967c92ef5 | 88 | char buffer[256]; |
ryanlin97 | 5:186967c92ef5 | 89 | pc.printf ("Enter a long number: "); |
ryanlin97 | 5:186967c92ef5 | 90 | fgets (buffer, 256, stdin); |
ryanlin97 | 5:186967c92ef5 | 91 | int angle = atoi (buffer); |
ryanlin97 | 5:186967c92ef5 | 92 | |
ryanlin97 | 5:186967c92ef5 | 93 | if(angle == 0) { |
ryanlin97 | 5:186967c92ef5 | 94 | pc.printf("invalid input try again\n"); |
ryanlin97 | 5:186967c92ef5 | 95 | } else { |
ryanlin97 | 5:186967c92ef5 | 96 | smart.pid_turn(angle); |
ryanlin97 | 5:186967c92ef5 | 97 | } |
ryanlin97 | 0:7e6b349182bc | 98 | |
ryanlin97 | 6:b8a1fa98707e | 99 | } else if(c == 'o') { |
ryanlin97 | 6:b8a1fa98707e | 100 | pc.printf("turning on\n"); |
ryanlin97 | 9:90bc440405b6 | 101 | char* temp = "turning on"; |
ryanlin97 | 9:90bc440405b6 | 102 | commandRead.data = temp; |
ryanlin97 | 9:90bc440405b6 | 103 | chatter.publish(&commandRead); |
ryanlin97 | 9:90bc440405b6 | 104 | /*on = 1; |
ryanlin97 | 6:b8a1fa98707e | 105 | wait(1); |
ryanlin97 | 9:90bc440405b6 | 106 | on = 0;*/ |
ryanlin97 | 9:90bc440405b6 | 107 | smart.turn_on(); |
ryanlin97 | 7:cead0e7b0c1e | 108 | c = 'z'; |
ryanlin97 | 6:b8a1fa98707e | 109 | } else if(c == 'f') { |
ryanlin97 | 6:b8a1fa98707e | 110 | pc.printf("turning off\n"); |
ryanlin97 | 9:90bc440405b6 | 111 | /*off = 1; |
ryanlin97 | 6:b8a1fa98707e | 112 | wait(1); |
ryanlin97 | 9:90bc440405b6 | 113 | off = 0;*/ |
ryanlin97 | 9:90bc440405b6 | 114 | smart.turn_off(); |
ryanlin97 | 7:cead0e7b0c1e | 115 | c = 'z'; |
ryanlin97 | 5:186967c92ef5 | 116 | } |
ryanlin97 | 5:186967c92ef5 | 117 | |
ryanlin97 | 5:186967c92ef5 | 118 | else if( c == 'm' || manual) { |
ryanlin97 | 5:186967c92ef5 | 119 | pc.printf("turning on joystick\n"); |
ryanlin97 | 5:186967c92ef5 | 120 | manual = true; |
ryanlin97 | 5:186967c92ef5 | 121 | t.reset(); |
ryanlin97 | 9:90bc440405b6 | 122 | received = false; |
ryanlin97 | 9:90bc440405b6 | 123 | |
ryanlin97 | 5:186967c92ef5 | 124 | while(manual) { |
ryanlin97 | 5:186967c92ef5 | 125 | smart.move(x,y); |
ryanlin97 | 9:90bc440405b6 | 126 | if(received) { |
ryanlin97 | 9:90bc440405b6 | 127 | char d = commandRead.data[0]; |
ryanlin97 | 9:90bc440405b6 | 128 | if( d == 'u') { |
ryanlin97 | 5:186967c92ef5 | 129 | pc.printf("turning off joystick\n"); |
ryanlin97 | 5:186967c92ef5 | 130 | manual = false; |
ryanlin97 | 5:186967c92ef5 | 131 | } |
ryanlin97 | 9:90bc440405b6 | 132 | received = false; |
ryanlin97 | 0:7e6b349182bc | 133 | } |
ryanlin97 | 0:7e6b349182bc | 134 | } |
ryanlin97 | 0:7e6b349182bc | 135 | } |
ryanlin97 | 5:186967c92ef5 | 136 | |
ryanlin97 | 5:186967c92ef5 | 137 | else { |
ryanlin97 | 5:186967c92ef5 | 138 | pc.printf("none \n"); |
ryanlin97 | 5:186967c92ef5 | 139 | smart.stop(); |
ryanlin97 | 5:186967c92ef5 | 140 | } |
ryanlin97 | 7:cead0e7b0c1e | 141 | received = false; |
ryanlin97 | 0:7e6b349182bc | 142 | } |
ryanlin97 | 0:7e6b349182bc | 143 | |
ryanlin97 | 0:7e6b349182bc | 144 | else { |
ryanlin97 | 5:186967c92ef5 | 145 | // pc.printf("Nothing pressed \n"); |
ryanlin97 | 0:7e6b349182bc | 146 | smart.stop(); |
ryanlin97 | 0:7e6b349182bc | 147 | } |
ryanlin97 | 8:347b10e6bdf8 | 148 | nh.spinOnce(); |
ryanlin97 | 0:7e6b349182bc | 149 | wait(process); |
ryanlin97 | 0:7e6b349182bc | 150 | } |
ryanlin97 | 0:7e6b349182bc | 151 | |
ryanlin97 | 0:7e6b349182bc | 152 | } |
ryanlin97 | 0:7e6b349182bc | 153 | |
ryanlin97 | 8:347b10e6bdf8 | 154 | |
ryanlin97 | 3:ef063fd4234e | 155 | |
ryanlin97 | 3:ef063fd4234e | 156 | |
ryanlin97 | 3:ef063fd4234e | 157 | |
ryanlin97 | 3:ef063fd4234e | 158 | |
ryanlin97 | 3:ef063fd4234e | 159 | |
ryanlin97 | 3:ef063fd4234e | 160 |