autotest: add option to not check current wp after set_current_wp

Sometimes a waypoint is set which we'll never emit as our current
waypoint (e.g. a JUMP)
This commit is contained in:
Peter Barker 2021-03-09 17:37:16 +11:00 committed by Peter Barker
parent 4a251bebbd
commit f78d7c3b25
2 changed files with 16 additions and 10 deletions

View File

@ -525,6 +525,7 @@ class AutoTestPlane(AutoTest):
"""Fly a mission from a file."""
self.progress("Flying mission %s" % filename)
num_wp = self.load_mission(filename, strict=strict)-1
self.set_current_waypoint(0, check_afterwards=False)
self.change_mode('AUTO')
self.wait_waypoint(1, num_wp, max_dist=60)
self.wait_groundspeed(0, 0.5, timeout=mission_timeout)
@ -2076,7 +2077,6 @@ class AutoTestPlane(AutoTest):
def fly_terrain_mission(self):
self.set_current_waypoint(1)
self.wait_ready_to_arm()
self.arm_vehicle()

View File

@ -4278,19 +4278,25 @@ class AutoTest(ABC):
target_sysid=target_sysid,
target_compid=target_compid)
def set_current_waypoint_using_mission_set_current(self,
seq,
target_sysid=1,
target_compid=1):
def set_current_waypoint_using_mission_set_current(
self,
seq,
target_sysid=1,
target_compid=1,
check_afterwards=True):
self.mav.mav.mission_set_current_send(target_sysid,
target_compid,
seq)
self.wait_current_waypoint(seq, timeout=10)
if check_afterwards:
self.wait_current_waypoint(seq, timeout=10)
def set_current_waypoint(self, seq, target_sysid=1, target_compid=1):
return self.set_current_waypoint_using_mission_set_current(seq,
target_sysid,
target_compid)
def set_current_waypoint(self, seq, target_sysid=1, target_compid=1, check_afterwards=True):
return self.set_current_waypoint_using_mission_set_current(
seq,
target_sysid,
target_compid,
check_afterwards=check_afterwards
)
def verify_parameter_values(self, parameter_stuff, max_delta=0.0):
bad = ""