teleop_keyboard_omni3.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 from __future__ import print_function
4 
5 import rospy
6 
7 from std_msgs.msg import Float64
8 
9 import sys, select, termios, tty
10 
11 msg = """
12 Reading from the keyboard !
13 ---------------------------
14 Moving around:
15  u i o
16  j k l
17  m , .
18 
19 For Holonomic mode (strafing), hold down the shift key:
20 ---------------------------
21  U I O
22  J K L
23  M < >
24 
25 
26 anything else : stop
27 
28 q/z : increase/decrease max speeds by 10%
29 
30 CTRL-C to quit
31 """
32 
33 moveBindings = {
34  'i':(-1,0,1),
35  'o':(-1,1,0),
36  'j':(1,1,1),
37  'l':(-1,-1,-1),
38  'u':(-1,0,1),
39  ',':(1,0,-1),
40  '.':(0,1,-1),
41  'm':(1,-1,0),
42  'O':(-1,1,0),
43  'I':(-1,0,1),
44  'J':(1,-2,1),
45  'L':(-1,2,-1),
46  'U':(0,-1,1),
47  '<':(1,0,-1),
48  '>':(0,1,-1),
49  'M':(1,-1,0),
50  }
51 
52 speedBindings={
53  'q':(1.1,1.1),
54  'z':(.9,.9),
55  }
56 
57 def getKey():
58  tty.setraw(sys.stdin.fileno())
59  key = sys.stdin.read(1)
60  termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
61  return key
62 
63 
64 def vels(speed):
65  return "currently:\tspeed %s " % (speed)
66 
67 if __name__=="__main__":
68  settings = termios.tcgetattr(sys.stdin)
69 
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)
74 
75 
76  speed = 1.0
77  x = 0
78  y = 0
79  z = 0
80  status = 0
81 
82  try:
83  print(msg)
84  print(vels(speed))
85  while(1):
86  key = getKey()
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]
93 
94  print(vels(speed))
95  if (status == 14):
96  print(msg)
97  status = (status + 1) % 15
98  else:
99  x = 0
100  y = 0
101  z = 0
102  th = 0
103  if (key == '\x03'):
104  break
105 
106  vell = Float64()
107  velb = Float64()
108  velr = Float64()
109 
110  vell = x*speed
111  velb = y*speed
112  velr = z*speed
113 
114  publ.publish(vell)
115  pubb.publish(velb)
116  pubr.publish(velr)
117 
118  except Exception as e:
119  print(e)
120 
121  finally:
122  vell = Float64()
123  velb = Float64()
124  velr = Float64()
125 
126  vell = 0.0
127  velb = 0.0
128  velr = 0.0
129 
130  pubb.publish(vell)
131  publ.publish(velb)
132  pubr.publish(velr)
133 
134  termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)


teleop_keyboard_omni3
Author(s): Yug Ajmera
autogenerated on Wed Nov 4 2020 03:44:44