def Start(self, vehicle): logger.log("+-+-+-+-+-+-+ Starting up %s +-+-+-+-+-+-+" % VERSION) ### initialize dronekit vehicle ### self.vehicle = vehicle ### switch vehicle to loiter mode ### self.vehicle.mode = VehicleMode("LOITER") ### initialize rc manager ### self.rcMgr = rcManager.rcManager(self) ### initialize app manager ### self.appMgr = appManager.appManager(self) ### initialize button manager ### self.buttonManager = buttonManager.buttonManager(self) ### initialize extended functions ### self.extFunctions = extFunctions.extFunctions(self.vehicle, self) ### initialize gopro manager ### self.goproManager = GoProManager.GoProManager(self) ### Initialize GeoFence manager ### self.geoFenceManager = GeoFenceManager.GeoFenceManager(self) # instantiate rewindManager self.rewindManager = rewindManager.RewindManager(self.vehicle, self) ### init APM stream rates ### self.initStreamRates() ### register callbacks ### self.registerCallbacks() # Try to maintain a constant tick rate self.timeOfLastTick = monotonic.monotonic() # how many ticks have we performed since an RC update? # register all connections (gopro manager communicates via appMgr's socket) self.inputs = [self.rcMgr.server, self.appMgr.server] self.outputs = [] #check if gimbal is present if self.vehicle.gimbal.yaw is not None: logger.log("[shot]: Gimbal detected.") # Initialize gimbal to RC targeting self.vehicle.gimbal.release() else: logger.log("[shot]: No gimbal detected.") # mark first tick time self.timeOfLastTick = monotonic.monotonic() # check for In-Air start from Shotmanager crash if self.vehicle.system_status == 'ACTIVE': logger.log("[shot]: Restart in air.") # load vehicle home self.rewindManager.loadHomeLocation()
def Start(self, vehicle): logger.log("+-+-+-+-+-+-+ Starting up %s +-+-+-+-+-+-+" % VERSION) ### initialize dronekit vehicle ### self.vehicle = vehicle ### switch vehicle to loiter mode ### self.vehicle.mode = VehicleMode("LOITER") ### initialize rc manager ### self.rcMgr = rcManager.rcManager(self) ### initialize app manager ### self.appMgr = appManager.appManager(self) ### initialize button manager ### self.buttonManager = buttonManager.buttonManager(self) ### initialize gopro manager ### self.goproManager = GoProManager.GoProManager(self) ### Initialize GeoFence manager ### self.geoFenceManager = GeoFenceManager.GeoFenceManager(self) # instantiate rewindManager self.rewindManager = rewindManager.RewindManager(self.vehicle, self) # Create a PyMata instance and initialize the object avoidance toggles self.led_left_state = 0 self.led_right_state = 0 self.led_center_state = 0 self.led_beam_angle_state = 0 self.center_collision_state = 0 try: self.arduinoBoard = PyMata("/dev/ttyACM0", verbose=True) self.arduinoBoard.set_pin_mode(COLL_RIGHT, self.arduinoBoard.INPUT, self.arduinoBoard.DIGITAL) self.arduinoBoard.set_pin_mode(COLL_CENTER, self.arduinoBoard.INPUT, self.arduinoBoard.DIGITAL) self.arduinoBoard.set_pin_mode(COLL_LEFT, self.arduinoBoard.INPUT, self.arduinoBoard.DIGITAL) self.arduinoBoard.set_pin_mode(SCAN_BIT1, self.arduinoBoard.INPUT, self.arduinoBoard.DIGITAL) self.arduinoBoard.set_pin_mode(SCAN_BIT2, self.arduinoBoard.INPUT, self.arduinoBoard.DIGITAL) self.arduinoBoard.set_pin_mode(SCAN_BIT3, self.arduinoBoard.INPUT, self.arduinoBoard.DIGITAL) self.arduinoBoard.set_pin_mode(SCAN_BIT4, self.arduinoBoard.INPUT, self.arduinoBoard.DIGITAL) except: logger.log("[shotmanager]: Error in communication to Arduino") ### init APM stream rates ### self.initStreamRates() ### register callbacks ### self.registerCallbacks() # Try to maintain a constant tick rate self.timeOfLastTick = monotonic.monotonic() # how many ticks have we performed since an RC update? # register all connections (gopro manager communicates via appMgr's socket) self.inputs = [self.rcMgr.server, self.appMgr.server] self.outputs = [] #check if gimbal is present if self.vehicle.gimbal.yaw is not None: logger.log("[shot]: Gimbal detected.") # Initialize gimbal to RC targeting self.vehicle.gimbal.release() else: logger.log("[shot]: No gimbal detected.") # mark first tick time self.timeOfLastTick = monotonic.monotonic() # check for In-Air start from Shotmanager crash if self.vehicle.system_status == 'ACTIVE': logger.log("[shot]: Restart in air.") # load vehicle home self.rewindManager.loadHomeLocation()