3 from __future__
import print_function
5 import roslib; roslib.load_manifest(
'teleop_twist_keyboard')
8 from geometry_msgs.msg
import Twist
10 import sys, select, termios, tty
13 Reading from the keyboard and Publishing to Twist! 14 --------------------------- 20 For Holonomic mode (strafing), hold down the shift key: 21 --------------------------- 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% 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)
77 return "currently:\tspeed %s\tturn %s " % (speed,turn)
79 if __name__==
"__main__":
80 settings = termios.tcgetattr(sys.stdin)
82 pub = rospy.Publisher(
'cmd_vel', Twist, queue_size = 1)
83 rospy.init_node(
'teleop_twist_keyboard')
85 speed = rospy.get_param(
"~speed", 0.5)
86 turn = rospy.get_param(
"~turn", 1.0)
95 print(
vels(speed,turn))
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]
107 print(
vels(speed,turn))
110 status = (status + 1) % 15
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
124 except Exception
as e:
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
133 termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)