3 from __future__
import print_function
7 import roslib; roslib.load_manifest(
'teleop_twist_keyboard')
10 from geometry_msgs.msg
import Twist
12 import sys, select, termios, tty
15 Reading from the keyboard and Publishing to Twist! 16 --------------------------- 22 For Holonomic mode (strafing), hold down the shift key: 23 --------------------------- 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% 72 super(PublishThread, self).
__init__()
73 self.
publisher = rospy.Publisher(
'cmd_vel', Twist, queue_size = 1)
94 while not rospy.is_shutdown()
and self.publisher.get_num_connections() == 0:
96 print(
"Waiting for subscriber to connect to {}".format(self.publisher.name))
100 if rospy.is_shutdown():
101 raise Exception(
"Got shutdown request before subscribers connected")
103 def update(self, x, y, z, th, speed, turn):
104 self.condition.acquire()
112 self.condition.notify()
113 self.condition.release()
117 self.
update(0, 0, 0, 0, 0, 0)
123 self.condition.acquire()
125 self.condition.wait(self.
timeout)
128 twist.linear.x = self.
x * self.
speed 129 twist.linear.y = self.
y * self.
speed 130 twist.linear.z = self.
z * self.
speed 133 twist.angular.z = self.
th * self.
turn 135 self.condition.release()
138 self.publisher.publish(twist)
147 self.publisher.publish(twist)
151 tty.setraw(sys.stdin.fileno())
152 rlist, _, _ = select.select([sys.stdin], [], [], key_timeout)
154 key = sys.stdin.read(1)
157 termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
162 return "currently:\tspeed %s\tturn %s " % (speed,turn)
164 if __name__==
"__main__":
165 settings = termios.tcgetattr(sys.stdin)
167 rospy.init_node(
'teleop_twist_keyboard')
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:
185 pub_thread.wait_for_subscribers()
186 pub_thread.update(x, y, z, th, speed, turn)
189 print(
vels(speed,turn))
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]
201 print(
vels(speed,turn))
204 status = (status + 1) % 15
208 if key ==
'' and x == 0
and y == 0
and z == 0
and th == 0:
217 pub_thread.update(x, y, z, th, speed, turn)
219 except Exception
as e:
225 termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
def update(self, x, y, z, th, speed, turn)
def wait_for_subscribers(self)