13 MAX_ROTATIONAL_SPEED = 0.3
    23 import tty, termios, sys
    24 from geometry_msgs.msg 
import Twist
    25 rospy.init_node(
'discrete_keyboard_teleop')
    26 roslib.load_manifest(
'pioneer_teleop')
    43 rotationalDirection = 0
    46 pub = rospy.Publisher(
'cmd_vel', Twist, queue_size=10)
    49 while(keyPress != KEY_Q) 
and (keyPress != KEY_Q2):
    51         print " - Wainting for key press \n"    52         print "      > Arrows = move robot \n"    53         print "      > +/- = change speed \n"    54         print "      > q = quit \n"    58         fd = sys.stdin.fileno()
    59         old_settings = termios.tcgetattr(fd)
    61                 tty.setraw(sys.stdin.fileno())
    62                 ch = sys.stdin.read(1)
    64                 termios.tcsetattr(fd, termios.TCSADRAIN, old_settings)
    69         if (keyPress == KEY_UP):
    72                 print "  >> Move forward at speed " + str(speed) + 
" for " + str(MOVE_TIME) + 
" sec\n"    73         elif (keyPress == KEY_DOWN):
    76                 print "  >> Move backward at speed " + str(speed) + 
" for " + str(MOVE_TIME) + 
" sec\n"    77         elif (keyPress == KEY_LEFT):
    78                 rotationalDirection = 1
    80                 print "  >> Turn left at speed " + str(speed) + 
" for " + str(MOVE_TIME) + 
" sec\n"    81         elif (keyPress == KEY_RIGHT):
    82                 rotationalDirection = -1
    84                 print "  >> Turn Right at speed " + str(speed) + 
" for " + str(MOVE_TIME) + 
" sec\n"    85         elif (keyPress == KEY_PLUS) 
and (speed < MAX_SPEED):
    87                 print "  >> Set speed to " + str(speed) + 
"\n"    88         elif (keyPress == KEY_PLUS):
    89                 print "  >> Maximum speed value already reached : " + str(MAX_SPEED)    
    90         elif (keyPress == KEY_MINUS) 
and (speed > 0.1):
    92                 print "  >> Set speed to " + str(speed) + 
"\n"    93         elif (keyPress == KEY_MINUS):
    94                 print "  >> Minimum speed value already reached : 0.1"    97                 if (speed > MAX_ROTATIONAL_SPEED):
    98                         rotationalSpeed = MAX_ROTATIONAL_SPEED
   100                         rotationalSpeed = speed
   103                 twist.linear.x = linearDirection * speed
   104                 twist.angular.z = rotationalDirection * rotationalSpeed
   108                 while(t2-t1 < MOVE_TIME):
   117                 rotationalSpeed = 0.0
   119                 rotationalDirection = 0