Skip to content

Commit

Permalink
autotest: add upload_rally_points_from_locations
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Oct 3, 2023
1 parent 41518a4 commit f72bfcc
Showing 1 changed file with 25 additions and 0 deletions.
25 changes: 25 additions & 0 deletions Tools/autotest/common.py
Original file line number Diff line number Diff line change
Expand Up @@ -4716,6 +4716,8 @@ def check_mission_item_upload_download(self, items, itype, mission_type, strict=
self.check_fence_items_same(items, downloaded_items, strict=strict)
elif mission_type == mavutil.mavlink.MAV_MISSION_TYPE_MISSION:
self.check_mission_waypoint_items_same(items, downloaded_items, strict=strict)
elif mission_type == mavutil.mavlink.MAV_MISSION_TYPE_RALLY:
self.check_mission_waypoint_items_same(items, downloaded_items, strict=strict)
else:
raise NotAchievedException("Unhandled")

Expand All @@ -4732,6 +4734,13 @@ def check_mission_upload_download(self, items, strict=True):
mavutil.mavlink.MAV_MISSION_TYPE_MISSION,
strict=strict)

def check_rally_upload_download(self, items):
self.check_mission_item_upload_download(
items,
"rally",
mavutil.mavlink.MAV_MISSION_TYPE_RALLY
)

def check_dflog_message_rates(self, log_filepath, message_rates):
reader = self.dfreader_for_path(log_filepath)

Expand Down Expand Up @@ -11121,6 +11130,22 @@ def upload_fences_from_locations(self,

self.check_fence_upload_download(items)

def rally_MISSION_ITEM_INT_from_loc(self, loc):
return self.create_MISSION_ITEM_INT(
mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT,
x=int(loc.lat*1e7),
y=int(loc.lng*1e7),
z=loc.alt,
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
mission_type=mavutil.mavlink.MAV_MISSION_TYPE_RALLY
)

def upload_rally_points_from_locations(self, rally_point_locs):
'''takes a sequence of locations, sets vehicle rally points to those locations'''
items = [self.rally_MISSION_ITEM_INT_from_loc(x) for x in rally_point_locs]
self.correct_wp_seq_numbers(items)
self.check_rally_upload_download(items)

def wait_for_initial_mode(self):
'''wait until we get a heartbeat with an expected initial mode (the
one specified in the vehicle constructor)'''
Expand Down

0 comments on commit f72bfcc

Please sign in to comment.