teleop_keyboard_omni3.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 from __future__ import print_function
00004 
00005 import rospy
00006 
00007 from std_msgs.msg import Float64
00008 
00009 import sys, select, termios, tty
00010 
00011 msg = """
00012 Reading from the keyboard !
00013 ---------------------------
00014 Moving around:
00015    u    i    o
00016    j    k    l
00017    m    ,    .
00018 
00019 For Holonomic mode (strafing), hold down the shift key:
00020 ---------------------------
00021    U    I    O
00022    J    K    L
00023    M    <    >
00024 
00025 
00026 anything else : stop
00027 
00028 q/z : increase/decrease max speeds by 10%
00029 
00030 CTRL-C to quit
00031 """
00032 
00033 moveBindings = {
00034         'i':(-1,0,1),
00035         'o':(-1,1,0),
00036         'j':(1,1,1),
00037         'l':(-1,-1,-1),
00038         'u':(-1,0,1),
00039         ',':(1,0,-1),
00040         '.':(0,1,-1),
00041         'm':(1,-1,0),  
00042         'O':(-1,1,0),
00043         'I':(-1,0,1),
00044         'J':(1,-2,1),
00045         'L':(-1,2,-1),
00046         'U':(0,-1,1),
00047         '<':(1,0,-1),
00048         '>':(0,1,-1),
00049         'M':(1,-1,0),  
00050     }
00051 
00052 speedBindings={
00053         'q':(1.1,1.1),
00054         'z':(.9,.9),
00055     }
00056 
00057 def getKey():
00058     tty.setraw(sys.stdin.fileno())
00059     key = sys.stdin.read(1)
00060     termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
00061     return key
00062 
00063 
00064 def vels(speed):
00065     return "currently:\tspeed %s " % (speed)
00066 
00067 if __name__=="__main__":
00068     settings = termios.tcgetattr(sys.stdin)
00069 
00070     rospy.init_node('vel_Publisher')
00071     publ = rospy.Publisher('/open_base/left_joint_velocity_controller/command', Float64, queue_size=1)
00072     pubb = rospy.Publisher('/open_base/back_joint_velocity_controller/command', Float64, queue_size=1)
00073     pubr = rospy.Publisher('/open_base/right_joint_velocity_controller/command', Float64, queue_size=1)
00074 
00075 
00076     speed = 1.0
00077     x = 0
00078     y = 0
00079     z = 0
00080     status = 0
00081 
00082     try:
00083         print(msg)
00084         print(vels(speed))
00085         while(1):
00086             key = getKey()
00087             if key in moveBindings.keys():
00088                 x = moveBindings[key][0]
00089                 y = moveBindings[key][1]
00090                 z = moveBindings[key][2]
00091             elif key in speedBindings.keys():
00092                 speed = speed * speedBindings[key][0]
00093        
00094                 print(vels(speed))
00095                 if (status == 14):
00096                     print(msg)
00097                 status = (status + 1) % 15
00098             else:
00099                 x = 0
00100                 y = 0
00101                 z = 0
00102                 th = 0
00103                 if (key == '\x03'):
00104                     break
00105 
00106             vell = Float64()
00107             velb = Float64()
00108             velr = Float64()
00109         
00110             vell = x*speed
00111             velb = y*speed
00112             velr = z*speed
00113 
00114             publ.publish(vell)
00115             pubb.publish(velb)
00116             pubr.publish(velr)
00117 
00118     except Exception as e:
00119         print(e)
00120 
00121     finally:
00122         vell = Float64()
00123         velb = Float64()
00124         velr = Float64()
00125         
00126         vell = 0.0
00127         velb = 0.0
00128         velr = 0.0
00129 
00130         pubb.publish(vell)
00131         publ.publish(velb)
00132         pubr.publish(velr)
00133 
00134         termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)


teleop_keyboard_omni3
Author(s): Yug Ajmera
autogenerated on Mon Jun 17 2019 20:00:10