3 from __future__
import print_function
7 import roslib; roslib.load_manifest(
'teleop_twist_keyboard')
10 from geometry_msgs.msg
import Twist
11 from geometry_msgs.msg
import TwistStamped
14 from select
import select
16 if sys.platform ==
'win32':
26 Reading from the keyboard and Publishing to Twist!
27 ---------------------------
33 For Holonomic mode (strafing), hold down the shift key:
34 ---------------------------
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%
83 super(PublishThread, self).
__init__()
84 self.
publisher = rospy.Publisher(
'cmd_vel', TwistMsg, queue_size = 1)
105 while not rospy.is_shutdown()
and self.
publisher.get_num_connections() == 0:
107 print(
"Waiting for subscriber to connect to {}".format(self.
publisher.name))
111 if rospy.is_shutdown():
112 raise Exception(
"Got shutdown request before subscribers connected")
114 def update(self, x, y, z, th, speed, turn):
128 self.
update(0, 0, 0, 0, 0, 0)
135 twist = twist_msg.twist
136 twist_msg.header.stamp = rospy.Time.now()
137 twist_msg.header.frame_id = twist_frame
142 twist_msg.header.stamp = rospy.Time.now()
148 twist.linear.x = self.
x * self.
speed
149 twist.linear.y = self.
y * self.
speed
150 twist.linear.z = self.
z * self.
speed
153 twist.angular.z = self.
th * self.
turn
171 if sys.platform ==
'win32':
173 key = msvcrt.getwch()
175 tty.setraw(sys.stdin.fileno())
177 rlist, _, _ = select([sys.stdin], [], [], timeout)
179 key = sys.stdin.read(1)
182 termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
186 if sys.platform ==
'win32':
188 return termios.tcgetattr(sys.stdin)
191 if sys.platform ==
'win32':
193 termios.tcsetattr(sys.stdin, termios.TCSADRAIN, old_settings)
196 return "currently:\tspeed %s\tturn %s " % (speed,turn)
198 if __name__==
"__main__":
201 rospy.init_node(
'teleop_twist_keyboard')
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",
'')
212 TwistMsg = TwistStamped
223 pub_thread.wait_for_subscribers()
224 pub_thread.update(x, y, z, th, speed, turn)
227 print(
vels(speed,turn))
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))
245 status = (status + 1) % 15
249 if key ==
'' and x == 0
and y == 0
and z == 0
and th == 0:
258 pub_thread.update(x, y, z, th, speed, turn)
260 except Exception
as e: