autotest: adjust current wp reset

This commit is contained in:
Peter Barker 2022-05-15 09:28:56 +10:00 committed by Randy Mackay
parent 77f98b4072
commit 7a7d7f91ef
2 changed files with 19 additions and 2 deletions

View File

@ -590,6 +590,7 @@ class AutoTestPlane(AutoTest):
self.disarm_wait(timeout=120)
self.progress("Flying home")
self.set_current_waypoint(0, check_afterwards=False)
self.takeoff(10)
self.set_parameter("LAND_TYPE", 0)
self.fly_home_land_and_disarm()
@ -617,6 +618,7 @@ class AutoTestPlane(AutoTest):
self.set_current_waypoint(0, check_afterwards=False)
self.progress("Flying home")
self.set_current_waypoint(0, check_afterwards=False)
self.takeoff(100)
self.set_parameter("LAND_TYPE", 0)
self.fly_home_land_and_disarm(timeout=240)
@ -750,7 +752,6 @@ class AutoTestPlane(AutoTest):
# tend to miss the final waypoint by a fair bit, and
# this is probably too noisy anyway?
self.wait_disarmed(timeout=timeout)
self.set_current_waypoint(0, check_afterwards=False)
def fly_flaps(self):
"""Test flaps functionality."""
@ -1775,6 +1776,8 @@ class AutoTestPlane(AutoTest):
)
self.fly_home_land_and_disarm()
self.set_current_waypoint(0, check_afterwards=False)
self.change_mode("MANUAL")
self.set_rc(3, 1000)

View File

@ -3692,7 +3692,13 @@ class AutoTest(ABC):
wp.z)
return wp_int
def load_mission_from_filepath(self, filepath, filename, target_system=1, target_component=1, strict=True):
def load_mission_from_filepath(self,
filepath,
filename,
target_system=1,
target_component=1,
strict=True,
reset_current_wp=True):
self.progress("Loading mission (%s)" % filename)
path = os.path.join(testdir, filepath, filename)
wploader = mavwp.MAVWPLoader(
@ -3702,6 +3708,11 @@ class AutoTest(ABC):
wploader.load(path)
wpoints_int = [self.wp_to_mission_item_int(x) for x in wploader.wpoints]
self.check_mission_upload_download(wpoints_int, strict=strict)
if reset_current_wp:
# ArduPilot doesn't reset the current waypoint by default
# we may be in auto mode and running waypoints, so we
# can't check the current waypoint after resetting it.
self.set_current_waypoint(0, check_afterwards=False)
return len(wpoints_int)
def load_mission_using_mavproxy(self, mavproxy, filename):
@ -6542,6 +6553,8 @@ Also, ignores heartbeats not from our target system'''
try:
self.check_rc_defaults()
self.change_mode(self.default_mode())
# ArduPilot can still move the current waypoint from 0,
# even if we are not in AUTO mode, so cehck_afterwards=False:
self.set_current_waypoint(0, check_afterwards=False)
self.drain_mav()
self.drain_all_pexpects()
@ -6660,6 +6673,7 @@ Also, ignores heartbeats not from our target system'''
if not self.is_tracker(): # FIXME - more to the point, fix Tracker's mission handling
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_ALL)
self.set_current_waypoint(0, check_afterwards=False)
tee.close()