From 148e2e751f9fdb00ad964494e1028e4a5b1eea86 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 19 Feb 2021 10:40:36 +1100 Subject: [PATCH] autotest: add set_current_waypoint --- Tools/autotest/common.py | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index a7ea433d18..8996d8695a 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -4073,6 +4073,20 @@ class AutoTest(ABC): mavutil.mavlink.enums["MAV_RESULT"][m.result].name)) break + def set_current_waypoint_using_mission_set_current(self, + seq, + target_sysid=1, + target_compid=1): + self.mav.mav.mission_set_current_send(target_sysid, + target_compid, + seq) + 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 verify_parameter_values(self, parameter_stuff, max_delta=0.0): bad = "" for param in parameter_stuff: