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


teleop_twist_keyboard
Author(s): Graylin Trevor Jay
autogenerated on Sun Dec 25 2022 03:56:17