12 MAX_ROTATIONAL_SPEED = 0.3
    22 import tty, termios, sys
    23 from geometry_msgs.msg 
import Twist
    24 rospy.init_node(
'keyboard_teleop')
    25 roslib.load_manifest(
'pioneer_teleop')
    43 rotationalDirection = 0
    48 pub = rospy.Publisher(
'cmd_vel', Twist, queue_size=10)
    51 while(keyPress != KEY_Q) 
and (keyPress != KEY_Q2):
    53         print " - Wainting for key press \n"    54         print "      > Arrows = move robot \n"    55         print "      > s = stop \n"    56         print "      > q = quit \n"    60         fd = sys.stdin.fileno()
    61         old_settings = termios.tcgetattr(fd)
    63                 tty.setraw(sys.stdin.fileno())
    64                 ch = sys.stdin.read(1)
    66                 termios.tcsetattr(fd, termios.TCSADRAIN, old_settings)
    71         if (keyPress == KEY_UP):
    73                 print "  >> Inscrement linear speed\n"    74         elif (keyPress == KEY_DOWN):
    76                 print "  >> Decrement linear speed\n"    77         elif (keyPress == KEY_LEFT):
    78                 rotationalDirection = 1
    79                 print "  >> Inscrement rotational speed\n"    80         elif (keyPress == KEY_RIGHT):
    81                 rotationalDirection = -1
    82                 print "  >> Decrement rotational speed\n"    83         elif (keyPress == KEY_S) 
or (keyPress == KEY_S2):
    87                 rotationalDirection = 0.0
    88                 print "  >> Stop robot\n"    90         newLinearSpeed = linearSpeed + linearDirection * 0.1
    91         newRotationalSpeed = rotationalSpeed + rotationalDirection * 0.1
    93         if (newLinearSpeed > MAX_SPEED) 
or (newLinearSpeed < MAX_SPEED*(-1)):
    94                 print "     Warning ! Maximum linar speed already reached\n"    96                 linearSpeed = newLinearSpeed
    98         if (newRotationalSpeed > MAX_SPEED) 
or (newRotationalSpeed < MAX_SPEED*(-1)):
    99                 print "     Warning ! Maximum rotational speed already reached\n"   101                 rotationalSpeed = newRotationalSpeed
   103         print "     Speed = (linar: "+ str(linearSpeed) +
", rotational: "+ str(rotationalSpeed) +
")\n"   107         twist.linear.x = linearSpeed
   108         twist.angular.z = rotationalSpeed
   111         while(t2-t1 < MOVE_TIME):
   117         rotationalDirection = 0