Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove support for v0.9 WAYPOINT* messages #1428

Merged
merged 1 commit into from
Jul 31, 2024
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
6 changes: 3 additions & 3 deletions MAVProxy/modules/lib/mission_item_protocol.py
Original file line number Diff line number Diff line change
Expand Up @@ -245,7 +245,7 @@ def cmd_status(self, args):
def mavlink_packet(self, m):
'''handle an incoming mavlink packet'''
mtype = m.get_type()
if mtype in ['WAYPOINT_COUNT', 'MISSION_COUNT']:
if mtype in ['MISSION_COUNT']:
if getattr(m, 'mission_type', 0) != self.mav_mission_type():
return
if self.wp_op is None:
Expand All @@ -261,7 +261,7 @@ def mavlink_packet(self, m):
self.wploader.expected_count = m.count
self.send_wp_requests()

elif mtype in ['WAYPOINT', 'MISSION_ITEM', 'MISSION_ITEM_INT'] and self.wp_op is not None:
elif mtype in ['MISSION_ITEM', 'MISSION_ITEM_INT'] and self.wp_op is not None:
if m.get_type() == 'MISSION_ITEM_INT':
if getattr(m, 'mission_type', 0) != self.mav_mission_type():
# this is not a mission item, likely fence
Expand Down Expand Up @@ -292,7 +292,7 @@ def mavlink_packet(self, m):
self.wp_requested = {}
self.wp_received = {}

elif mtype in ["WAYPOINT_REQUEST", "MISSION_REQUEST"]:
elif mtype in ["MISSION_REQUEST"]:
self.process_waypoint_request(m, self.master)

def idle_task(self):
Expand Down
2 changes: 1 addition & 1 deletion MAVProxy/modules/mavproxy_console.py
Original file line number Diff line number Diff line change
Expand Up @@ -619,7 +619,7 @@ def mavlink_packet(self, msg):
fg = 'orange'

self.console.set_status('Link%u'%m.linknum, linkline, row=1, fg=fg)
elif type in ['WAYPOINT_CURRENT', 'MISSION_CURRENT']:
elif type in ['MISSION_CURRENT']:
wpmax = self.module('wp').wploader.count()
if wpmax > 0:
wpmax = "/%u" % wpmax
Expand Down
2 changes: 1 addition & 1 deletion MAVProxy/modules/mavproxy_horizon.py
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ def mavlink_packet(self, msg):
elif msgType == 'SYS_STATUS':
# Mode and Arm State
self.msgList.append(BatteryInfo(msg))
elif msgType in ['WAYPOINT_CURRENT', 'MISSION_CURRENT']:
elif msgType in ['MISSION_CURRENT']:
# Waypoints
self.currentWP = msg.seq
self.finalWP = self.module('wp').wploader.count()
Expand Down
6 changes: 3 additions & 3 deletions MAVProxy/modules/mavproxy_misseditor/mission_editor.py
Original file line number Diff line number Diff line change
Expand Up @@ -258,7 +258,7 @@ def mavlink_packet(self, m):
m.mission_type != mavutil.mavlink.MAV_MISSION_TYPE_MISSION):
return
mtype = m.get_type()
if mtype in ['WAYPOINT_COUNT','MISSION_COUNT', 'WAYPOINT', 'MISSION_ITEM', 'MISSION_ITEM_INT']:
if mtype in ['MISSION_COUNT', 'MISSION_ITEM', 'MISSION_ITEM_INT']:
if mtype == 'MISSION_ITEM_INT':
m = self.mpstate.module('wp').wp_from_mission_item_int(m)
self.mavlink_message_queue.put(m)
Expand All @@ -272,7 +272,7 @@ def process_mavlink_packet(self, m):
if (getattr(m, 'mission_type', None) is not None and
m.mission_type != mavutil.mavlink.MAV_MISSION_TYPE_MISSION):
return
if mtype in ['WAYPOINT_COUNT','MISSION_COUNT']:
if mtype in ['MISSION_COUNT']:
if (self.num_wps_expected == 0):
#I haven't asked for WPs, or these messages are duplicates
#of msgs I've already received.
Expand All @@ -294,7 +294,7 @@ def process_mavlink_packet(self, m):
#since this is a write operation from the Editor there
#should be no need to update number of table rows

elif mtype in ['WAYPOINT', 'MISSION_ITEM']:
elif mtype in ['MISSION_ITEM']:
#still expecting wps?
if (len(self.wps_received) < self.num_wps_expected):
#if we haven't already received this wp, write it to the GUI:
Expand Down
8 changes: 4 additions & 4 deletions MAVProxy/modules/mavproxy_oldwp.py
Original file line number Diff line number Diff line change
Expand Up @@ -143,7 +143,7 @@ def wp_status(self):
def mavlink_packet(self, m):
'''handle an incoming mavlink packet'''
mtype = m.get_type()
if mtype in ['WAYPOINT_COUNT', 'MISSION_COUNT']:
if mtype in ['MISSION_COUNT']:
if getattr(m, 'mission_type', 0) != 0:
# this is not a mission item, likely fence
return
Expand All @@ -159,7 +159,7 @@ def mavlink_packet(self, m):
self.wploader.expected_count = m.count
self.send_wp_requests()

elif mtype in ['WAYPOINT', 'MISSION_ITEM', 'MISSION_ITEM_INT'] and self.wp_op is not None:
elif mtype in ['MISSION_ITEM', 'MISSION_ITEM_INT'] and self.wp_op is not None:
if m.get_type() == 'MISSION_ITEM_INT':
if getattr(m, 'mission_type', 0) != 0:
# this is not a mission item, likely fence
Expand Down Expand Up @@ -190,10 +190,10 @@ def mavlink_packet(self, m):
self.wp_requested = {}
self.wp_received = {}

elif mtype in ["WAYPOINT_REQUEST", "MISSION_REQUEST"]:
elif mtype in ["MISSION_REQUEST"]:
self.process_waypoint_request(m, self.master)

elif mtype in ["WAYPOINT_CURRENT", "MISSION_CURRENT"]:
elif mtype in ["MISSION_CURRENT"]:
if m.seq != self.last_waypoint:
self.last_waypoint = m.seq
if self.settings.wpupdates:
Expand Down
2 changes: 1 addition & 1 deletion MAVProxy/modules/mavproxy_wp.py
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ def mavlink_packet(self, m):
'''handle an incoming mavlink packet'''
mtype = m.get_type()

if mtype in ["WAYPOINT_CURRENT", "MISSION_CURRENT"]:
if mtype in ["MISSION_CURRENT"]:
if m.seq != self.last_waypoint:
self.last_waypoint = m.seq
if self.settings.wpupdates:
Expand Down