3 from __future__ 
import print_function
     7 from std_msgs.msg 
import Float64
     9 import sys, select, termios, tty
    12 Reading from the keyboard !    13 ---------------------------    19 For Holonomic mode (strafing), hold down the shift key:    20 ---------------------------    28 q/z : increase/decrease max speeds by 10%    58     tty.setraw(sys.stdin.fileno())
    59     key = sys.stdin.read(1)
    60     termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
    65     return "currently:\tspeed %s " % (speed)
    67 if __name__==
"__main__":
    68     settings = termios.tcgetattr(sys.stdin)
    70     rospy.init_node(
'vel_Publisher')
    71     publ = rospy.Publisher(
'/open_base/left_joint_velocity_controller/command', Float64, queue_size=1)
    72     pubb = rospy.Publisher(
'/open_base/back_joint_velocity_controller/command', Float64, queue_size=1)
    73     pubr = rospy.Publisher(
'/open_base/right_joint_velocity_controller/command', Float64, queue_size=1)
    87             if key 
in moveBindings.keys():
    88                 x = moveBindings[key][0]
    89                 y = moveBindings[key][1]
    90                 z = moveBindings[key][2]
    91             elif key 
in speedBindings.keys():
    92                 speed = speed * speedBindings[key][0]
    97                 status = (status + 1) % 15
   118     except Exception 
as e:
   134         termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)