added code to ToF and inserted the e_button
Dependencies: Version1-4
Dependents: Version1-4 Version1-3
main.cpp@5:90bf5f0d86e9, 2018-08-13 (annotated)
- Committer:
- ryanlin97
- Date:
- Mon Aug 13 21:54:37 2018 +0000
- Revision:
- 5:90bf5f0d86e9
- Parent:
- 0:7e6b349182bc
- Child:
- 6:e9b1684a9c00
small board
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 | 5:90bf5f0d86e9 | 10 | ] |
ryanlin97 | 0:7e6b349182bc | 11 | bool manual = false; |
ryanlin97 | 0:7e6b349182bc | 12 | |
ryanlin97 | 0:7e6b349182bc | 13 | Serial pc(USBTX, USBRX, 57600); |
ryanlin97 | 5:90bf5f0d86e9 | 14 | |
ryanlin97 | 0:7e6b349182bc | 15 | Timer t; |
ryanlin97 | 0:7e6b349182bc | 16 | EventQueue queue; |
ryanlin97 | 0:7e6b349182bc | 17 | |
ryanlin97 | 0:7e6b349182bc | 18 | //MPU9250 imu(D14, D15); |
ryanlin97 | 0:7e6b349182bc | 19 | Wheelchair smart(xDir,yDir, &pc, &t); |
ryanlin97 | 0:7e6b349182bc | 20 | Thread thread; |
ryanlin97 | 0:7e6b349182bc | 21 | |
ryanlin97 | 5:90bf5f0d86e9 | 22 | void messageCb(const std_msgs::String& command){ |
ryanlin97 | 5:90bf5f0d86e9 | 23 | myled = 1; // turn on the led |
ryanlin97 | 5:90bf5f0d86e9 | 24 | commandRead.data = command.data; |
ryanlin97 | 5:90bf5f0d86e9 | 25 | } |
ryanlin97 | 5:90bf5f0d86e9 | 26 | |
ryanlin97 | 5:90bf5f0d86e9 | 27 | ros::Subscriber<std_msgs::String> sub("toggle_led", &messageCb); |
ryanlin97 | 5:90bf5f0d86e9 | 28 | |
ryanlin97 | 0:7e6b349182bc | 29 | int main(void) |
ryanlin97 | 0:7e6b349182bc | 30 | { |
ryanlin97 | 0:7e6b349182bc | 31 | queue.call_every(SAMPLEFREQ, &smart, &Wheelchair::compass_thread); |
ryanlin97 | 0:7e6b349182bc | 32 | t.reset(); |
ryanlin97 | 0:7e6b349182bc | 33 | thread.start(callback(&queue, &EventQueue::dispatch_forever)); |
ryanlin97 | 0:7e6b349182bc | 34 | while(1) { |
ryanlin97 | 0:7e6b349182bc | 35 | if( pc.readable()) { |
ryanlin97 | 0:7e6b349182bc | 36 | char c = pc.getc(); |
ryanlin97 | 0:7e6b349182bc | 37 | |
ryanlin97 | 0:7e6b349182bc | 38 | if( c == 'w') { |
ryanlin97 | 0:7e6b349182bc | 39 | pc.printf("up \n"); |
ryanlin97 | 0:7e6b349182bc | 40 | smart.forward(); |
ryanlin97 | 0:7e6b349182bc | 41 | } |
ryanlin97 | 0:7e6b349182bc | 42 | |
ryanlin97 | 0:7e6b349182bc | 43 | else if( c == 'a') { |
ryanlin97 | 0:7e6b349182bc | 44 | //pc.printf("left \n"); |
ryanlin97 | 0:7e6b349182bc | 45 | smart.left(); |
ryanlin97 | 0:7e6b349182bc | 46 | } |
ryanlin97 | 0:7e6b349182bc | 47 | |
ryanlin97 | 0:7e6b349182bc | 48 | else if( c == 'd') { |
ryanlin97 | 0:7e6b349182bc | 49 | //pc.printf("right \n"); |
ryanlin97 | 0:7e6b349182bc | 50 | smart.right(); |
ryanlin97 | 0:7e6b349182bc | 51 | } |
ryanlin97 | 0:7e6b349182bc | 52 | |
ryanlin97 | 0:7e6b349182bc | 53 | else if( c == 's') { |
ryanlin97 | 0:7e6b349182bc | 54 | pc.printf("down \n"); |
ryanlin97 | 0:7e6b349182bc | 55 | smart.backward(); |
ryanlin97 | 0:7e6b349182bc | 56 | } |
ryanlin97 | 0:7e6b349182bc | 57 | |
ryanlin97 | 0:7e6b349182bc | 58 | else if( c == 'r') { |
ryanlin97 | 0:7e6b349182bc | 59 | smart.turn_right(90); |
ryanlin97 | 0:7e6b349182bc | 60 | } |
ryanlin97 | 0:7e6b349182bc | 61 | |
ryanlin97 | 0:7e6b349182bc | 62 | else if( c == 'l') { |
ryanlin97 | 0:7e6b349182bc | 63 | smart.turn_left(90); |
ryanlin97 | 0:7e6b349182bc | 64 | } |
ryanlin97 | 0:7e6b349182bc | 65 | |
ryanlin97 | 0:7e6b349182bc | 66 | else if( c == 't') { |
ryanlin97 | 0:7e6b349182bc | 67 | char buffer[256]; |
ryanlin97 | 0:7e6b349182bc | 68 | pc.printf ("Enter a long number: "); |
ryanlin97 | 0:7e6b349182bc | 69 | fgets (buffer, 256, stdin); |
ryanlin97 | 0:7e6b349182bc | 70 | int angle = atoi (buffer); |
ryanlin97 | 0:7e6b349182bc | 71 | |
ryanlin97 | 0:7e6b349182bc | 72 | if(angle == 0) { |
ryanlin97 | 0:7e6b349182bc | 73 | pc.printf("invalid input try again\n"); |
ryanlin97 | 0:7e6b349182bc | 74 | } else { |
ryanlin97 | 0:7e6b349182bc | 75 | smart.pid_turn(angle); |
ryanlin97 | 0:7e6b349182bc | 76 | } |
ryanlin97 | 0:7e6b349182bc | 77 | |
ryanlin97 | 0:7e6b349182bc | 78 | } |
ryanlin97 | 0:7e6b349182bc | 79 | |
ryanlin97 | 0:7e6b349182bc | 80 | else if( c == 'm' || manual) { |
ryanlin97 | 0:7e6b349182bc | 81 | pc.printf("turning on joystick\n"); |
ryanlin97 | 0:7e6b349182bc | 82 | manual = true; |
ryanlin97 | 0:7e6b349182bc | 83 | t.reset(); |
ryanlin97 | 0:7e6b349182bc | 84 | while(manual) { |
ryanlin97 | 0:7e6b349182bc | 85 | smart.move(x,y); |
ryanlin97 | 0:7e6b349182bc | 86 | if( pc.readable()) { |
ryanlin97 | 0:7e6b349182bc | 87 | char d = pc.getc(); |
ryanlin97 | 0:7e6b349182bc | 88 | if( d == 'm') { |
ryanlin97 | 0:7e6b349182bc | 89 | pc.printf("turning off joystick\n"); |
ryanlin97 | 0:7e6b349182bc | 90 | manual = false; |
ryanlin97 | 0:7e6b349182bc | 91 | } |
ryanlin97 | 0:7e6b349182bc | 92 | } |
ryanlin97 | 0:7e6b349182bc | 93 | } |
ryanlin97 | 0:7e6b349182bc | 94 | } |
ryanlin97 | 0:7e6b349182bc | 95 | |
ryanlin97 | 0:7e6b349182bc | 96 | else { |
ryanlin97 | 0:7e6b349182bc | 97 | pc.printf("none \n"); |
ryanlin97 | 0:7e6b349182bc | 98 | smart.stop(); |
ryanlin97 | 0:7e6b349182bc | 99 | } |
ryanlin97 | 0:7e6b349182bc | 100 | } |
ryanlin97 | 0:7e6b349182bc | 101 | |
ryanlin97 | 0:7e6b349182bc | 102 | else { |
ryanlin97 | 0:7e6b349182bc | 103 | // pc.printf("Nothing pressed \n"); |
ryanlin97 | 0:7e6b349182bc | 104 | smart.stop(); |
ryanlin97 | 0:7e6b349182bc | 105 | } |
ryanlin97 | 0:7e6b349182bc | 106 | wait(process); |
ryanlin97 | 0:7e6b349182bc | 107 | } |
ryanlin97 | 0:7e6b349182bc | 108 | |
ryanlin97 | 0:7e6b349182bc | 109 | } |
ryanlin97 | 0:7e6b349182bc | 110 | |
ryanlin97 | 5:90bf5f0d86e9 | 111 | |
ryanlin97 | 5:90bf5f0d86e9 | 112 | |
ryanlin97 | 5:90bf5f0d86e9 | 113 | |
ryanlin97 | 5:90bf5f0d86e9 | 114 |