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 roslib; roslib.load_manifest('teleop_twist_keyboard')
6 import rospy
7 
8 from geometry_msgs.msg import Twist
9 
10 import sys, select, termios, tty
11 
12 msg = """
13 Reading from the keyboard and Publishing to Twist!
14 ---------------------------
15 Moving around:
16  u i o
17  j k l
18  m , .
19 
20 For Holonomic mode (strafing), hold down the shift key:
21 ---------------------------
22  U I O
23  J K L
24  M < >
25 
26 t : up (+z)
27 b : down (-z)
28 
29 anything else : stop
30 
31 q/z : increase/decrease max speeds by 10%
32 w/x : increase/decrease only linear speed by 10%
33 e/c : increase/decrease only angular speed by 10%
34 
35 CTRL-C to quit
36 """
37 
38 moveBindings = {
39  'i':(1,0,0,0),
40  'o':(1,0,0,-1),
41  'j':(0,0,0,1),
42  'l':(0,0,0,-1),
43  'u':(1,0,0,1),
44  ',':(-1,0,0,0),
45  '.':(-1,0,0,1),
46  'm':(-1,0,0,-1),
47  'O':(1,-1,0,0),
48  'I':(1,0,0,0),
49  'J':(0,1,0,0),
50  'L':(0,-1,0,0),
51  'U':(1,1,0,0),
52  '<':(-1,0,0,0),
53  '>':(-1,-1,0,0),
54  'M':(-1,1,0,0),
55  't':(0,0,1,0),
56  'b':(0,0,-1,0),
57  }
58 
59 speedBindings={
60  'q':(1.1,1.1),
61  'z':(.9,.9),
62  'w':(1.1,1),
63  'x':(.9,1),
64  'e':(1,1.1),
65  'c':(1,.9),
66  }
67 
68 def getKey():
69  tty.setraw(sys.stdin.fileno())
70  select.select([sys.stdin], [], [], 0)
71  key = sys.stdin.read(1)
72  termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
73  return key
74 
75 
76 def vels(speed,turn):
77  return "currently:\tspeed %s\tturn %s " % (speed,turn)
78 
79 if __name__=="__main__":
80  settings = termios.tcgetattr(sys.stdin)
81 
82  pub = rospy.Publisher('cmd_vel', Twist, queue_size = 1)
83  rospy.init_node('teleop_twist_keyboard')
84 
85  speed = rospy.get_param("~speed", 0.5)
86  turn = rospy.get_param("~turn", 1.0)
87  x = 0
88  y = 0
89  z = 0
90  th = 0
91  status = 0
92 
93  try:
94  print(msg)
95  print(vels(speed,turn))
96  while(1):
97  key = getKey()
98  if key in moveBindings.keys():
99  x = moveBindings[key][0]
100  y = moveBindings[key][1]
101  z = moveBindings[key][2]
102  th = moveBindings[key][3]
103  elif key in speedBindings.keys():
104  speed = speed * speedBindings[key][0]
105  turn = turn * speedBindings[key][1]
106 
107  print(vels(speed,turn))
108  if (status == 14):
109  print(msg)
110  status = (status + 1) % 15
111  else:
112  x = 0
113  y = 0
114  z = 0
115  th = 0
116  if (key == '\x03'):
117  break
118 
119  twist = Twist()
120  twist.linear.x = x*speed; twist.linear.y = y*speed; twist.linear.z = z*speed;
121  twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = th*turn
122  pub.publish(twist)
123 
124  except Exception as e:
125  print(e)
126 
127  finally:
128  twist = Twist()
129  twist.linear.x = 0; twist.linear.y = 0; twist.linear.z = 0
130  twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = 0
131  pub.publish(twist)
132 
133  termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)


teleop_twist_keyboard
Author(s): Graylin Trevor Jay
autogenerated on Sun Mar 10 2019 02:21:52