keyboard_control.py 5.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176
  1. #!/usr/bin/env python
  2. import rospy
  3. from geometry_msgs.msg import Twist
  4. import sys
  5. import select
  6. import termios
  7. import tty
  8. def get_key_non_blocking():
  9. """???????"""
  10. fd = sys.stdin.fileno()
  11. old_settings = termios.tcgetattr(fd)
  12. try:
  13. tty.setraw(fd)
  14. # ???????
  15. if select.select([sys.stdin], [], [], 0.05)[0]:
  16. key = sys.stdin.read(1)
  17. else:
  18. key = 'None' # ????
  19. finally:
  20. termios.tcsetattr(fd, termios.TCSADRAIN, old_settings)
  21. return key
  22. def get_key():
  23. tty.setraw(sys.stdin.fileno())
  24. select.select([sys.stdin], [], [], 0)
  25. key = sys.stdin.read(1)
  26. termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
  27. return key
  28. def clamp(value, min_value, max_value):
  29. return max(min(value, max_value), min_value)
  30. if __name__ == "__main__":
  31. settings = termios.tcgetattr(sys.stdin)
  32. rospy.init_node('keyboard_control')
  33. pub = rospy.Publisher('/cmd_vel', Twist, queue_size=10)
  34. max_linear = 0.8
  35. max_angular = 0.6
  36. speed_increment = 0.05
  37. decay_rate = 0.02
  38. linear_speed = 0.0
  39. angular_speed = 0.0
  40. active_keys = set()
  41. rate = rospy.Rate(15)
  42. try:
  43. print "Control the robot with keyboard:"
  44. print "w/x: Increase/Decrease linear speed"
  45. print "a/d: Increase/Decrease angular speed"
  46. print "s: Stop"
  47. print "Ctrl+C: Exit"
  48. while not rospy.is_shutdown():
  49. # if sys.stdin in select.select([sys.stdin], [], [], 0)[0]:
  50. # key = get_key()
  51. key = get_key_non_blocking()
  52. if key == 'w':
  53. active_keys.add('w')
  54. elif key == 'x':
  55. active_keys.add('x')
  56. elif key == 'a':
  57. active_keys.add('a')
  58. elif key == 'd':
  59. active_keys.add('d')
  60. elif key == 'q':
  61. active_keys.add('q')
  62. elif key == 'e':
  63. active_keys.add('e')
  64. elif key == 's':
  65. active_keys.clear()
  66. linear_speed = 0.0
  67. angular_speed = 0.0
  68. print "Robot stopped."
  69. elif key == '1':
  70. max_linear += 0.1
  71. print "max_linear = {:.2f}, max_angular = {:.2f}".format(max_linear, max_angular)
  72. elif key == '2':
  73. max_linear -= 0.1
  74. print "max_linear = {:.2f}, max_angular = {:.2f}".format(max_linear, max_angular)
  75. elif key == '3':
  76. max_angular += 0.1
  77. print "max_linear = {:.2f}, max_angular = {:.2f}".format(max_linear, max_angular)
  78. elif key == '4':
  79. max_angular -= 0.1
  80. print "max_linear = {:.2f}, max_angular = {:.2f}".format(max_linear, max_angular)
  81. elif key == '\x03': # Ctrl+C
  82. break
  83. else:
  84. # print "Invalid key! Use 'w', 'x', 'a', 'd', or 's'."
  85. pass
  86. # Process active keys
  87. if 'q' in active_keys:
  88. if linear_speed + speed_increment < max_linear: # w
  89. linear_speed += speed_increment
  90. else:
  91. linear_speed = max_linear
  92. if angular_speed + speed_increment < max_angular: # a
  93. angular_speed += speed_increment
  94. else:
  95. angular_speed = max_angular
  96. if 'e' in active_keys:
  97. if linear_speed + speed_increment < max_linear: # w
  98. linear_speed += speed_increment
  99. # linear_speed = 0.4
  100. else:
  101. linear_speed = max_linear
  102. if angular_speed - speed_increment > -max_angular: # d
  103. angular_speed -= speed_increment
  104. else:
  105. angular_speed = -max_angular
  106. if 'w' in active_keys:
  107. if linear_speed + speed_increment < max_linear:
  108. linear_speed += speed_increment
  109. else:
  110. linear_speed = max_linear
  111. elif 'x' in active_keys:
  112. if linear_speed - speed_increment > -max_linear:
  113. linear_speed -= speed_increment
  114. else:
  115. linear_speed = -max_linear
  116. else:
  117. if linear_speed > 0.03:
  118. linear_speed -= decay_rate # ????
  119. elif linear_speed < -0.03:
  120. linear_speed += decay_rate # ????
  121. else:
  122. linear_speed = 0.0
  123. if 'a' in active_keys:
  124. if angular_speed + speed_increment < max_angular:
  125. angular_speed += speed_increment
  126. else:
  127. angular_speed = max_angular
  128. elif 'd' in active_keys:
  129. if angular_speed - speed_increment > -max_angular:
  130. angular_speed -= speed_increment
  131. else:
  132. angular_speed = -max_angular
  133. else:
  134. if angular_speed > 0.03:
  135. angular_speed -= decay_rate # ????
  136. elif angular_speed < -0.03:
  137. angular_speed += decay_rate # ????
  138. else:
  139. angular_speed = 0.0
  140. # Remove released keys
  141. active_keys -= {'w', 'x', 'a', 'd', 'q', 'e'}
  142. # Publish Twist message
  143. twist = Twist()
  144. twist.linear.x = linear_speed
  145. twist.angular.z = angular_speed
  146. pub.publish(twist)
  147. if linear_speed != 0.0 or angular_speed != 0.0:
  148. print "Linear speed: {:.2f}, Angular speed: {:.2f}".format(linear_speed, angular_speed)
  149. rate.sleep()
  150. except rospy.ROSInterruptException:
  151. pass
  152. finally:
  153. termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)