def wp_ftp_upload(self, filename): '''upload waypoints to vehicle with ftp''' ftp = self.mpstate.module('ftp') if ftp is None: print("Need ftp module") return self.wploader.target_system = self.target_system self.wploader.target_component = self.target_component try: #need to remove the leading and trailing quotes in filename self.wploader.load(filename.strip('"')) except Exception as msg: print("Unable to load %s - %s" % (filename, msg)) return print("Loaded %u waypoints from %s" % (self.wploader.count(), filename)) print("Sending mission with ftp") fh = SIO() fh.write(struct.pack("<HHHHH", 0x763d,mavutil.mavlink.MAV_MISSION_TYPE_MISSION,0,0,self.wploader.count())) mavmsg = mavutil.mavlink.MAVLink_mission_item_int_message for i in range(self.wploader.count()): w = self.wploader.wp(i) w = self.wp_to_mission_item_int(w) tlist = [] for field in mavmsg.ordered_fieldnames: tlist.append(getattr(w, field)) tlist = tuple(tlist) buf = struct.pack(mavmsg.format, *tlist) fh.write(buf) fh.seek(0) self.upload_start = time.time() ftp.cmd_put([self.mission_ftp_name, self.mission_ftp_name], fh=fh, callback=self.ftp_upload_callback, progress_callback=self.ftp_upload_progress)
def ftp_load(self, filename, param_wildcard, master): '''load parameters with ftp''' ftp = self.mpstate.module('ftp') if ftp is None: print("Need ftp module") return newparm = mavparm.MAVParmDict() newparm.load(filename, param_wildcard, check=False) fh = SIO() for k in sorted(newparm.keys()): v = newparm.get(k) oldv = self.mav_param.get(k, None) if oldv is not None and abs(oldv - v) <= newparm.mindelta: # not changed newparm.pop(k) count = len(newparm.keys()) if count == 0: print("No parameter changes") return fh.write(struct.pack("<HHH", 0x671b, count, count)) last_param = "" for k in sorted(newparm.keys()): v = newparm.get(k) vtype = self.best_type(v) common_len = self.str_common_len(last_param, k) b1 = vtype b2 = common_len | ((len(k) - (common_len + 1)) << 4) fh.write(struct.pack("<BB", b1, b2)) fh.write(k[common_len:].encode("UTF-8")) if vtype == 1: # int8 fh.write(struct.pack("<b", int(v))) if vtype == 2: # int16 fh.write(struct.pack("<h", int(v))) if vtype == 3: # int32 fh.write(struct.pack("<i", int(v))) if vtype == 4: # float fh.write(struct.pack("<f", v)) last_param = k # re-pack with full file length in total_params file_len = fh.tell() fh.seek(0) fh.write(struct.pack("<HHH", 0x671b, count, file_len)) fh.seek(0) self.ftp_send_param = newparm print("Sending %u params" % count) ftp.cmd_put(["-", "@PARAM/param.pck"], fh=fh, callback=self.ftp_upload_callback, progress_callback=self.ftp_upload_progress)
def send_to_port(host, port, payload): for res in socket.getaddrinfo(host, port, socket.AF_INET, socket.SOCK_STREAM): af, socktype, proto, canonname, sa = res received = SIO() s = socket.socket(af, socktype, proto) try: s.connect(sa) s.send(payload) for tmp in s.recv(1024): received.write(tmp) return received.getvalue() finally: s.close() received.close()
def handle_open_RO_reply(self, op, m): '''handle OP_OpenFileRO reply''' if op.opcode == OP_Ack: if self.filename is None: return try: if self.callback is not None or self.filename == '-': self.fh = SIO() else: self.fh = open(self.filename, 'wb') except Exception as ex: print("Failed to open %s: %s" % (self.filename, ex)) self.terminate_session() return read = FTP_OP(self.seq, self.session, OP_BurstReadFile, self.burst_size, 0, 0, 0, None) self.last_burst_read = time.time() self.send(read) else: if self.callback is None or self.ftp_settings.debug > 0: print("ftp open failed") self.terminate_session()
def response_content(self): content = self.response.content.decode('UTF-8') pagesource = etree.parse(SIO(content), etree.HTMLParser()) return pagesource