mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
autotest: add set_current_waypoint
This commit is contained in:
parent
bf7920f2d7
commit
148e2e751f
@ -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:
|
||||
|
Loading…
Reference in New Issue
Block a user