14 from geometry_msgs.msg
import Twist
18 def __init__(self, min_velocity, max_velocity, num_steps):
19 assert min_velocity > 0
and max_velocity > 0
and num_steps > 0
31 Takes a value in the range [0, 1] and the step and returns the 32 velocity (usually m/s or rad/s). 39 return value * max_value
49 self._screen.nodelay(
True)
55 keycode = self._screen.getch()
56 return keycode
if keycode != -1
else None 63 raise ValueError,
'lineno out of bounds' 64 height, width = self._screen.getmaxyx()
67 for text
in message.split(
'\n'):
68 text = text.ljust(width)
69 self._screen.addstr(y, x, text)
73 self._screen.refresh()
87 self.
_pub_cmd = rospy.Publisher(
'key_vel', Twist)
89 self.
_hz = rospy.get_param(
'~hz', 10)
93 forward_min = rospy.get_param(
'~turbo/linear_forward_min', 0.5)
94 forward_max = rospy.get_param(
'~turbo/linear_forward_max', 1.0)
97 backward_min = rospy.get_param(
'~turbo/linear_backward_min', 0.25)
98 backward_max = rospy.get_param(
'~turbo/linear_backward_max', 0.5)
101 angular_min = rospy.get_param(
'~turbo/angular_min', 0.7)
102 angular_max = rospy.get_param(
'~turbo/angular_max', 1.2)
109 rate = rospy.Rate(self.
_hz)
111 keycode = self._interface.read_key()
122 twist.linear.x = self.
_forward(1.0, linear)
124 twist.linear.x = self.
_backward(-1.0, -linear)
125 twist.angular.z = self.
_rotation(math.copysign(1, angular), abs(angular))
129 movement_bindings = {
130 curses.KEY_UP: ( 1, 0),
131 curses.KEY_DOWN: (-1, 0),
132 curses.KEY_LEFT: ( 0, 1),
133 curses.KEY_RIGHT: ( 0, -1),
138 if keycode
in movement_bindings:
139 acc = movement_bindings[keycode]
152 self._interface.beep()
153 elif keycode
in speed_bindings:
154 acc = speed_bindings[keycode]
156 if acc[0]
is not None:
158 if acc[1]
is not None:
161 elif keycode == ord(
'q'):
162 rospy.signal_shutdown(
'Bye')
169 self._interface.clear()
170 self._interface.write_line(2,
'Linear: %d, Angular: %d' % (self.
_linear, self.
_angular))
171 self._interface.write_line(5,
'Use arrow keys to move, space to stop, q to exit.')
172 self._interface.refresh()
175 self._pub_cmd.publish(twist)
183 self.
_hz = rospy.get_param(
'~hz', 10)
192 movement_bindings = {
193 curses.KEY_UP: ( 1, 0),
194 curses.KEY_DOWN: (-1, 0),
195 curses.KEY_LEFT: ( 0, 1),
196 curses.KEY_RIGHT: ( 0, -1),
200 rate = rospy.Rate(self.
_hz)
204 keycode = self._interface.read_key()
214 twist.linear.x = linear
215 twist.angular.z = angular
219 now = rospy.get_time()
239 if keycode == ord(
'q'):
241 rospy.signal_shutdown(
'Bye')
246 self._interface.clear()
247 self._interface.write_line(2,
'Linear: %f, Angular: %f' % (self.
_linear, self.
_angular))
248 self._interface.write_line(5,
'Use arrow keys to move, q to exit.')
249 self._interface.refresh()
252 self._pub_cmd.publish(twist)
256 rospy.init_node(
'key_teleop')
260 if __name__ ==
'__main__':
263 except rospy.ROSInterruptException:
def _key_pressed(self, keycode)
def _get_twist(self, linear, angular)
def __init__(self, min_velocity, max_velocity, num_steps)
def _get_twist(self, linear, angular)
def __init__(self, interface)
def __init__(self, interface)
def __init__(self, stdscr, lines=10)
def _key_pressed(self, keycode)
def write_line(self, lineno, message)
def __call__(self, value, step)
dictionary movement_bindings