teleop_twist_keyboard.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 from __future__ import print_function
4 
5 import threading
6 
7 import roslib; roslib.load_manifest('teleop_twist_keyboard')
8 import rospy
9 
10 from geometry_msgs.msg import Twist
11 
12 import sys, select, termios, tty
13 
14 msg = """
15 Reading from the keyboard and Publishing to Twist!
16 ---------------------------
17 Moving around:
18  u i o
19  j k l
20  m , .
21 
22 For Holonomic mode (strafing), hold down the shift key:
23 ---------------------------
24  U I O
25  J K L
26  M < >
27 
28 t : up (+z)
29 b : down (-z)
30 
31 anything else : stop
32 
33 q/z : increase/decrease max speeds by 10%
34 w/x : increase/decrease only linear speed by 10%
35 e/c : increase/decrease only angular speed by 10%
36 
37 CTRL-C to quit
38 """
39 
40 moveBindings = {
41  'i':(1,0,0,0),
42  'o':(1,0,0,-1),
43  'j':(0,0,0,1),
44  'l':(0,0,0,-1),
45  'u':(1,0,0,1),
46  ',':(-1,0,0,0),
47  '.':(-1,0,0,1),
48  'm':(-1,0,0,-1),
49  'O':(1,-1,0,0),
50  'I':(1,0,0,0),
51  'J':(0,1,0,0),
52  'L':(0,-1,0,0),
53  'U':(1,1,0,0),
54  '<':(-1,0,0,0),
55  '>':(-1,-1,0,0),
56  'M':(-1,1,0,0),
57  't':(0,0,1,0),
58  'b':(0,0,-1,0),
59  }
60 
61 speedBindings={
62  'q':(1.1,1.1),
63  'z':(.9,.9),
64  'w':(1.1,1),
65  'x':(.9,1),
66  'e':(1,1.1),
67  'c':(1,.9),
68  }
69 
70 class PublishThread(threading.Thread):
71  def __init__(self, rate):
72  super(PublishThread, self).__init__()
73  self.publisher = rospy.Publisher('cmd_vel', Twist, queue_size = 1)
74  self.x = 0.0
75  self.y = 0.0
76  self.z = 0.0
77  self.th = 0.0
78  self.speed = 0.0
79  self.turn = 0.0
80  self.condition = threading.Condition()
81  self.done = False
82 
83  # Set timeout to None if rate is 0 (causes new_message to wait forever
84  # for new data to publish)
85  if rate != 0.0:
86  self.timeout = 1.0 / rate
87  else:
88  self.timeout = None
89 
90  self.start()
91 
93  i = 0
94  while not rospy.is_shutdown() and self.publisher.get_num_connections() == 0:
95  if i == 4:
96  print("Waiting for subscriber to connect to {}".format(self.publisher.name))
97  rospy.sleep(0.5)
98  i += 1
99  i = i % 5
100  if rospy.is_shutdown():
101  raise Exception("Got shutdown request before subscribers connected")
102 
103  def update(self, x, y, z, th, speed, turn):
104  self.condition.acquire()
105  self.x = x
106  self.y = y
107  self.z = z
108  self.th = th
109  self.speed = speed
110  self.turn = turn
111  # Notify publish thread that we have a new message.
112  self.condition.notify()
113  self.condition.release()
114 
115  def stop(self):
116  self.done = True
117  self.update(0, 0, 0, 0, 0, 0)
118  self.join()
119 
120  def run(self):
121  twist = Twist()
122  while not self.done:
123  self.condition.acquire()
124  # Wait for a new message or timeout.
125  self.condition.wait(self.timeout)
126 
127  # Copy state into twist message.
128  twist.linear.x = self.x * self.speed
129  twist.linear.y = self.y * self.speed
130  twist.linear.z = self.z * self.speed
131  twist.angular.x = 0
132  twist.angular.y = 0
133  twist.angular.z = self.th * self.turn
134 
135  self.condition.release()
136 
137  # Publish.
138  self.publisher.publish(twist)
139 
140  # Publish stop message when thread exits.
141  twist.linear.x = 0
142  twist.linear.y = 0
143  twist.linear.z = 0
144  twist.angular.x = 0
145  twist.angular.y = 0
146  twist.angular.z = 0
147  self.publisher.publish(twist)
148 
149 
150 def getKey(key_timeout):
151  tty.setraw(sys.stdin.fileno())
152  rlist, _, _ = select.select([sys.stdin], [], [], key_timeout)
153  if rlist:
154  key = sys.stdin.read(1)
155  else:
156  key = ''
157  termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
158  return key
159 
160 
161 def vels(speed, turn):
162  return "currently:\tspeed %s\tturn %s " % (speed,turn)
163 
164 if __name__=="__main__":
165  settings = termios.tcgetattr(sys.stdin)
166 
167  rospy.init_node('teleop_twist_keyboard')
168 
169  speed = rospy.get_param("~speed", 0.5)
170  turn = rospy.get_param("~turn", 1.0)
171  repeat = rospy.get_param("~repeat_rate", 0.0)
172  key_timeout = rospy.get_param("~key_timeout", 0.0)
173  if key_timeout == 0.0:
174  key_timeout = None
175 
176  pub_thread = PublishThread(repeat)
177 
178  x = 0
179  y = 0
180  z = 0
181  th = 0
182  status = 0
183 
184  try:
185  pub_thread.wait_for_subscribers()
186  pub_thread.update(x, y, z, th, speed, turn)
187 
188  print(msg)
189  print(vels(speed,turn))
190  while(1):
191  key = getKey(key_timeout)
192  if key in moveBindings.keys():
193  x = moveBindings[key][0]
194  y = moveBindings[key][1]
195  z = moveBindings[key][2]
196  th = moveBindings[key][3]
197  elif key in speedBindings.keys():
198  speed = speed * speedBindings[key][0]
199  turn = turn * speedBindings[key][1]
200 
201  print(vels(speed,turn))
202  if (status == 14):
203  print(msg)
204  status = (status + 1) % 15
205  else:
206  # Skip updating cmd_vel if key timeout and robot already
207  # stopped.
208  if key == '' and x == 0 and y == 0 and z == 0 and th == 0:
209  continue
210  x = 0
211  y = 0
212  z = 0
213  th = 0
214  if (key == '\x03'):
215  break
216 
217  pub_thread.update(x, y, z, th, speed, turn)
218 
219  except Exception as e:
220  print(e)
221 
222  finally:
223  pub_thread.stop()
224 
225  termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
def update(self, x, y, z, th, speed, turn)


teleop_twist_keyboard
Author(s): Graylin Trevor Jay
autogenerated on Thu Jul 2 2020 03:51:51