Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
29 changes: 16 additions & 13 deletions MAVProxy/modules/lib/mission_item_protocol.py
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,7 @@ def __init__(self, mpstate, name, description, **args):

def gui_menu_items(self):
return [
MPMenuItem('FTP', 'FTP', '# %s ftp' % self.command_name()),
MPMenuItem('Clear', 'Clear', '# %s clear' % self.command_name()),
MPMenuItem('List', 'List', '# %s list' % self.command_name()),
MPMenuItem(
Expand Down Expand Up @@ -863,6 +864,8 @@ def commands(self):
print("%s module not available; use old compat modules" % str(self.itemtype()))
return
return {
"ftp": self.wp_ftp_download,
"ftpload": self.wp_ftp_upload,
"clear": self.cmd_clear,
"list": self.cmd_list,
"load": (self.cmd_load, ["(FILENAME)"]),
Expand Down Expand Up @@ -962,7 +965,7 @@ def request_list_send(self):
mission_type=self.mav_mission_type())

def wp_ftp_download(self, args):
'''Download wpts from vehicle with ftp'''
'''Download items from vehicle with ftp'''
ftp = self.mpstate.module('ftp')
if ftp is None:
print("Need ftp module")
Expand All @@ -971,7 +974,7 @@ def wp_ftp_download(self, args):
ftp.cmd_get([self.mission_ftp_name()], callback=self.ftp_callback, callback_progress=self.ftp_callback_progress)

def ftp_callback_progress(self, fh, total_size):
'''progress callback from ftp fetch of mission'''
'''progress callback from ftp fetch of mission items'''
if self.ftp_count is None and total_size >= 10:
ofs = fh.tell()
fh.seek(0)
Expand All @@ -987,18 +990,18 @@ def ftp_callback_progress(self, fh, total_size):
self.mpstate.console.set_status('Mission', 'Mission %u/%u' % (done, self.ftp_count))

def ftp_callback(self, fh):
'''callback from ftp fetch of mission'''
'''callback from ftp fetch of mission items'''
if fh is None:
print("mission: failed ftp download")
return
magic = 0x763d
data = fh.read()
magic2, dtype, options, start, num_items = struct.unpack("<HHHHH", data[0:10])
if magic != magic2:
print("mission: bad magic 0x%x expected 0x%x" % (magic2, magic))
print("%s: bad magic 0x%x expected 0x%x" % (self.itemtype(), magic2, magic))
return
if dtype != mavutil.mavlink.MAV_MISSION_TYPE_MISSION:
print("mission: bad data type %u" % dtype)
if dtype != self.mav_mission_type():
print("%s: bad data type %u" % (self.itemtype(), dtype))
return

self.wploader.clear()
Expand Down Expand Up @@ -1051,11 +1054,11 @@ def wp_ftp_upload(self, args):
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")
print("Loaded %u %s from %s" % (self.wploader.count(), self.itemstype(), filename))
print("Sending %s with ftp" % self.itemstype())

fh = SIO()
fh.write(struct.pack("<HHHHH", 0x763d, mavutil.mavlink.MAV_MISSION_TYPE_MISSION, 0, 0, self.wploader.count()))
fh.write(struct.pack("<HHHHH", 0x763d, self.mav_mission_type(), 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)
Expand All @@ -1074,18 +1077,18 @@ def wp_ftp_upload(self, args):
fh=fh, callback=self.ftp_upload_callback, progress_callback=self.ftp_upload_progress)

def ftp_upload_progress(self, proportion):
'''callback from ftp put of mission'''
'''callback from ftp put of items'''
if proportion is None:
self.mpstate.console.set_status('Mission', 'Mission ERR')
else:
count = self.wploader.count()
self.mpstate.console.set_status('Mission', 'Mission %u/%u' % (int(proportion*count), count))

def ftp_upload_callback(self, dlen):
'''callback from ftp put of mission'''
'''callback from ftp put of items'''
if dlen is None:
print("Failed to send waypoints")
print("Failed to send %s" % self.itemstype())
else:
mavmsg = mavutil.mavlink.MAVLink_mission_item_int_message
item_size = mavmsg.unpacker.size
print("Sent mission of length %u in %.2fs" % ((dlen - 10) // item_size, time.time() - self.upload_start))
print("Sent %s of length %u in %.2fs" % (self.itemtype(), (dlen - 10) // item_size, time.time() - self.upload_start))
3 changes: 3 additions & 0 deletions MAVProxy/modules/mavproxy_fence.py
Original file line number Diff line number Diff line change
Expand Up @@ -167,6 +167,9 @@ def returnpoint(self):
return p
return None

def mission_ftp_name(self):
return "@MISSION/fence.dat"

@staticmethod
def loader_class():
return mavwp.MissionItemProtocol_Fence
Expand Down
2 changes: 1 addition & 1 deletion MAVProxy/modules/mavproxy_rally.py
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@ def commands(self):
return ret

def mission_ftp_name(self):
return "@MISSION/fence.dat"
return "@MISSION/rally.dat"

@staticmethod
def loader_class():
Expand Down
3 changes: 0 additions & 3 deletions MAVProxy/modules/mavproxy_wp.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@ def __init__(self, mpstate):
def gui_menu_items(self):
ret = super(WPModule, self).gui_menu_items()
ret.extend([
MPMenuItem('FTP', 'FTP', '# %s ftp' % self.command_name()),
MPMenuItem('Editor', 'Editor', '# wp editor'),
MPMenuItem(
'Draw', 'Draw', '# wp draw ',
Expand Down Expand Up @@ -177,8 +176,6 @@ def commands(self):
"add_landing": self.wp_add_landing,
"add_rtl": self.wp_add_RTL,
"add_dls": self.wp_add_dls,
"ftp": self.wp_ftp_download,
"ftpload": self.wp_ftp_upload,
"update": (self.cmd_update, ["(FILENAME)"]),
"undo": self.cmd_undo,
})
Expand Down