add checking for up or down with sshkeyboard¨v
This commit is contained in:
@@ -12,16 +12,16 @@ class TestController(Node):
|
||||
def __init__(self):
|
||||
super().__init__('test_controller')
|
||||
self.cli = self.create_client(SetAttitude, 'drone/set_attitude')
|
||||
# while not self.cli.wait_for_service(timeout_sec=1.0):
|
||||
# self.get_logger().info('service not available, waiting again...')
|
||||
while not self.cli.wait_for_service(timeout_sec=1.0):
|
||||
self.get_logger().info('service not available, waiting again...')
|
||||
self.req = SetAttitude.Request()
|
||||
|
||||
self.get_logger().info("Controls:\nW - forward\nS - backward\nA - left\nD - right\nQ - rotate left\nE - rotate right\nSpace - up\nShift - down\nEsc - exit")
|
||||
|
||||
def spin(self):
|
||||
while rclpy.ok():
|
||||
asyncio.run(listen_keyboard_manual(on_press=self.on_press))
|
||||
rclpy.spin_once(self, timeout_sec=0.1)
|
||||
def spin(self):
|
||||
while rclpy.ok():
|
||||
asyncio.run(listen_keyboard_manual(on_press=self.on_press))
|
||||
rclpy.spin_once(self, timeout_sec=0.1)
|
||||
|
||||
def send_request(self, yaw, pitch, roll, thrust):
|
||||
self.req.yaw = yaw
|
||||
@@ -44,27 +44,35 @@ class TestController(Node):
|
||||
if key == 'w':
|
||||
self.get_logger().info('forward')
|
||||
self.send_request(pitch=-10.0, yaw=0.0,
|
||||
roll=0.0, thrust=0.0)
|
||||
roll=0.0, thrust=0.0)
|
||||
if key == 's':
|
||||
self.get_logger().info('backward')
|
||||
self.send_request(pitch=10.0, yaw=0.0,
|
||||
roll=0.0, thrust=0.0)
|
||||
roll=0.0, thrust=0.0)
|
||||
if key == 'a':
|
||||
self.get_logger().info('left')
|
||||
self.send_request(pitch=0.0, yaw=0.0,
|
||||
roll=-10.0, thrust=0.0)
|
||||
roll=-10.0, thrust=0.0)
|
||||
if key == 'd':
|
||||
self.get_logger().info('right')
|
||||
self.send_request(pitch=0.0, yaw=0.0,
|
||||
roll=10.0, thrust=0.0)
|
||||
roll=10.0, thrust=0.0)
|
||||
if key == 'q':
|
||||
self.get_logger().info('rotate left')
|
||||
self.send_request(pitch=0.0, yaw=-10.0,
|
||||
roll=0.0, thrust=0.0)
|
||||
roll=0.0, thrust=0.0)
|
||||
if key == 'e':
|
||||
self.get_logger().info('rotate right')
|
||||
self.send_request(pitch=0.0, yaw=10.0,
|
||||
roll=0.0, thrust=0.0)
|
||||
roll=0.0, thrust=0.0)
|
||||
if key == 'z':
|
||||
self.get_logger().info('down')
|
||||
self.send_request(pitch=0.0, yaw=0.0,
|
||||
roll=0.0, thrust=-0.05)
|
||||
if key == 'space':
|
||||
self.get_logger().info('down')
|
||||
self.send_request(pitch=0.0, yaw=0.0,
|
||||
roll=0.0, thrust=-0.05)
|
||||
# else:
|
||||
# try:
|
||||
# # known keys like spacebar, ctrl
|
||||
|
||||
Reference in New Issue
Block a user