def cmd_fw_download(self, args): '''cmd handler for downloading firmware''' stuff = self.filtered_rows_from_args(args) if stuff is None: return (filtered, remainder) = stuff if len(filtered) == 0: print("fw: No firmware specified") return if len(filtered) > 1: print("fw: No single firmware specified") return firmware = filtered[0]["_firmware"] url = firmware["url"] try: print("fw: URL: %s" % (url,)) filename=os.path.basename(url) files = [] files.append((url,filename)) child = multiproc.Process(target=mp_util.download_files, args=(files,)) child.start() except Exception as e: print("fw: download failed") print(e)
def createFileList(self): """SRTM data is split into different directories, get a list of all of them and create a dictionary for easy lookup.""" global childFileListDownload global filelistDownloadActive mypid = os.getpid() if mypid not in childFileListDownload or not childFileListDownload[mypid].is_alive(): childFileListDownload[mypid] = multiproc.Process(target=self.createFileListHTTP) filelistDownloadActive = 1 childFileListDownload[mypid].start() filelistDownloadActive = 0
def getTile(self, lat, lon): """Get a SRTM tile object. This function can return either an SRTM1 or SRTM3 object depending on what is available, however currently it only returns SRTM3 objects.""" global childFileListDownload global filelistDownloadActive mypid = os.getpid() if mypid in childFileListDownload and childFileListDownload[mypid].is_alive(): if self.debug: print("still getting file list") return 0 elif not os.path.isfile(self.filelist_file) and filelistDownloadActive == 0: self.createFileList() return 0 elif not self.filelist: if self.debug: print("Filelist download complete, loading data ", self.filelist_file) data = open(self.filelist_file, 'rb') self.filelist = pickle.load(data) data.close() try: continent, filename = self.filelist[(int(lat), int(lon))] except KeyError: if len(self.filelist) > self.min_filelist_len: # we appear to have a full filelist - this must be ocean return SRTMOceanTile(int(lat), int(lon)) return 0 global childTileDownload mypid = os.getpid() if not os.path.exists(os.path.join(self.cachedir, filename)): if not mypid in childTileDownload or not childTileDownload[mypid].is_alive(): try: childTileDownload[mypid] = multiproc.Process(target=self.downloadTile, args=(str(continent), str(filename))) childTileDownload[mypid].start() except Exception as ex: if mypid in childTileDownload: childTileDownload.pop(mypid) return 0 '''print("Getting Tile")''' return 0 elif mypid in childTileDownload and childTileDownload[mypid].is_alive(): '''print("Still Getting Tile")''' return 0 # TODO: Currently we create a new tile object each time. # Caching is required for improved performance. try: return SRTMTile(os.path.join(self.cachedir, filename), int(lat), int(lon)) except InvalidTileError: return 0
def param_help_download(self): '''download XML files for parameters''' files = [] for vehicle in ['Rover', 'ArduCopter', 'ArduPlane', 'ArduSub', 'AntennaTracker']: url = 'http://autotest.ardupilot.org/Parameters/%s/apm.pdef.xml.gz' % vehicle path = mp_util.dot_mavproxy("%s.xml" % vehicle) files.append((url, path)) url = 'http://autotest.ardupilot.org/%s-defaults.parm' % vehicle if vehicle != 'AntennaTracker': # defaults not generated for AntennaTracker ATM path = mp_util.dot_mavproxy("%s-defaults.parm" % vehicle) files.append((url, path)) try: child = multiproc.Process(target=mp_util.download_files, args=(files,)) child.start() except Exception as e: print(e)
def __init__(self, title='SlipMap', lat=-35.362938, lon=149.165085, width=800, height=600, ground_width=1000, tile_delay=0.3, service="MicrosoftSat", max_zoom=19, debug=False, brightness=0, elevation=False, download=True, show_flightmode_legend=True, timelim_pipe=None): self.lat = lat self.lon = lon self.width = width self.height = height self.ground_width = ground_width self.download = download self.service = service self.tile_delay = tile_delay self.debug = debug self.max_zoom = max_zoom self.elevation = elevation self.oldtext = None self.brightness = brightness self.legend = show_flightmode_legend self.timelim_pipe = timelim_pipe self.drag_step = 10 self.title = title self.event_queue = multiproc.Queue() self.object_queue = multiproc.Queue() self.close_window = multiproc.Semaphore() self.close_window.acquire() self.child = multiproc.Process(target=self.child_task) self.child.start() self._callbacks = set()
def show(self): t = multiproc.Process(target=self.call) t.start()