
for ros integration
Dependencies: wheelchaircontrolRos
Fork of wheelchaircontrolrealtime by
Revision 5:186967c92ef5, committed 2018-08-13
- Comitter:
- ryanlin97
- Date:
- Mon Aug 13 21:53:21 2018 +0000
- Parent:
- 4:db3aa99ab312
- Child:
- 6:b8a1fa98707e
- Commit message:
- while loop;
Changed in this revision
main.cpp | Show annotated file Show diff for this revision Revisions of this file |
--- a/main.cpp Mon Aug 13 21:43:02 2018 +0000 +++ b/main.cpp Mon Aug 13 21:53:21 2018 +0000 @@ -48,73 +48,79 @@ t.reset(); thread.start(callback(&queue, &EventQueue::dispatch_forever)); setupNode(); - if(received) { - - if( c == 'w') { - pc.printf("up \n"); - smart.forward(); - } + while(1) { + if( received) { - else if( c == 'a') { - //pc.printf("left \n"); - smart.left(); - } + if( c == 'w') { + pc.printf("up \n"); + smart.forward(); + } - else if( c == 'd') { - //pc.printf("right \n"); - smart.right(); - } + else if( c == 'a') { + //pc.printf("left \n"); + smart.left(); + } - else if( c == 's') { - pc.printf("down \n"); - smart.backward(); - } - - else if( c == 'r') { - smart.turn_right(90); - } + else if( c == 'd') { + //pc.printf("right \n"); + smart.right(); + } - else if( c == 'l') { - smart.turn_left(90); - } + else if( c == 's') { + pc.printf("down \n"); + smart.backward(); + } - else if( c == 't') { - char buffer[256]; - pc.printf ("Enter a long number: "); - fgets (buffer, 256, stdin); - int angle = atoi (buffer); + else if( c == 'r') { + smart.turn_right(90); + } - if(angle == 0) { - pc.printf("invalid input try again\n"); - } else { - smart.pid_turn(angle); + else if( c == 'l') { + smart.turn_left(90); } - } + else if( c == 't') { + char buffer[256]; + pc.printf ("Enter a long number: "); + fgets (buffer, 256, stdin); + int angle = atoi (buffer); + + if(angle == 0) { + pc.printf("invalid input try again\n"); + } else { + smart.pid_turn(angle); + } - else if( c == 'm' || manual) { - pc.printf("turning on joystick\n"); - manual = true; - t.reset(); - while(manual) { - smart.move(x,y); - if( pc.readable()) { - char d = pc.getc(); - if( d == 'm') { - pc.printf("turning off joystick\n"); - manual = false; + } + + else if( c == 'm' || manual) { + pc.printf("turning on joystick\n"); + manual = true; + t.reset(); + while(manual) { + smart.move(x,y); + if( pc.readable()) { + char d = pc.getc(); + if( d == 'm') { + pc.printf("turning off joystick\n"); + manual = false; + } } } } + + else { + pc.printf("none \n"); + smart.stop(); + } } else { - pc.printf("none \n"); + // pc.printf("Nothing pressed \n"); smart.stop(); } - + received = !received; wait(process); - received = !received; } }