6 from geometry_msgs.msg
import Twist
8 import sys, select, termios, tty
11 Reading from the keyboard and Publishing to Twist! 12 --------------------------- 17 For Holonomic mode (strafing), hold down the shift key: 18 --------------------------- 25 q/z : increase/decrease max speeds by 10% 26 w/x : increase/decrease only linear speed by 10% 27 e/c : increase/decrease only angular speed by 10% 62 tty.setraw(sys.stdin.fileno())
63 select.select([sys.stdin], [], [], 0)
64 key = sys.stdin.read(1)
65 termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
70 return "currently:\tspeed %s\tturn %s " % (speed,turn)
72 if __name__==
"__main__":
73 settings = termios.tcgetattr(sys.stdin)
75 pub = rospy.Publisher(
'/cmd_vel', Twist, queue_size = 1)
76 rospy.init_node(
'teleop_twist_keyboard')
78 speed = rospy.get_param(
"~speed", 0.5)
79 turn = rospy.get_param(
"~turn", 1.0)
88 print vels(speed,turn)
91 if key
in moveBindings.keys():
92 x = moveBindings[key][0]
93 y = moveBindings[key][1]
94 z = moveBindings[key][2]
95 th = moveBindings[key][3]
96 elif key
in speedBindings.keys():
97 speed = speed * speedBindings[key][0]
98 turn = turn * speedBindings[key][1]
100 print vels(speed,turn)
103 status = (status + 1) % 15
113 twist.linear.x = x*speed; twist.linear.y = y*speed; twist.linear.z = z*speed;
114 twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = th*turn
122 twist.linear.x = 0; twist.linear.y = 0; twist.linear.z = 0
123 twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = 0
126 termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)