def takeoff(z=1.5, safe_takeoff=True, frame_id='map', timeout=5.0, use_leds=True, interrupter=interrupt_event): print(interrupter.is_set()) if use_leds: LedLib.wipe_to(255, 0, 0, interrupter=interrupter) if interrupter.is_set(): return result = FlightLib.takeoff(z=z, wait=False, timeout_takeoff=timeout, frame_id=frame_id, emergency_land=safe_takeoff, interrupter=interrupter) if result == 'not armed': raise Exception( 'STOP' ) # Raise exception to clear task_manager if copter can't arm if interrupter.is_set(): return if use_leds: LedLib.blink(0, 255, 0, wait=50, interrupter=interrupter)
def run(self): self.connect() red = 0 green = 0 blue = 0 while True: data = self.fetch_data() if 'color' in data: data = data.split()[1:] color = map(int, data) red, green, blue = color elif data == 'rainbow': LedLib.rainbow() elif data == 'fill': LedLib.fill(red, green, blue) elif data == 'blink': LedLib.blink(red, green, blue) elif data == 'chase': LedLib.chase(red, green, blue) elif data == 'wipe_to': LedLib.wipe_to(red, green, blue) elif data == 'fade_to': LedLib.fade_to(red, green, blue) elif data == 'run': LedLib.fade_to(red, green, blue) elif data == 'close': LedLib.off() time.sleep(0.001)
import time from FlightLib import FlightLib as f, LedLib as led f.init('SingleCleverFlight') led.wipe_to(0, 255, 0) f.takeoff(1.5) led.rainbow() #rectangle f.reach(0.25, 0.25, 1.2) led.fade_to(255, 0, 0) f.reach(1, 0.25, 1.2) led.fade_to(0, 255, 0) f.reach(1, 2.2, 1.2) led.fade_to(0, 0, 255) f.reach(0.25, 2.2, 1.2) led.fade_to(255, 255, 0) f.reach(0.25, 0.25, 1.2) led.fade_to(255, 0, 0) #center_spin f.reach(0.7, 1.1, 1.5) led.run(255, 0, 255, length=15, direction=True) f.spin(yaw_rate=0.6)
def takeoff(): FlightLib.takeoff() LedLib.wipe_to(0, 255, 0)