mirror of https://github.com/ArduPilot/ardupilot
Tools: sub: update to new wait functions
Signed-off-by: Pierre Kancir <pierre.kancir.emn@gmail.com>
This commit is contained in:
parent
aba594fe2d
commit
f24f97e51b
|
@ -104,7 +104,7 @@ class AutoTestSub(AutoTest):
|
|||
|
||||
|
||||
self.set_rc(Joystick.Throttle, 1000)
|
||||
self.wait_altitude(alt_min=-6, alt_max=-5)
|
||||
self.wait_altitude(altitude_min=-6, altitude_max=-5)
|
||||
self.set_rc(Joystick.Throttle, 1500)
|
||||
|
||||
# let the vehicle settle (momentum / stopping point shenanigans....)
|
||||
|
@ -113,7 +113,7 @@ class AutoTestSub(AutoTest):
|
|||
self.watch_altitude_maintained()
|
||||
|
||||
self.set_rc(Joystick.Throttle, 1000)
|
||||
self.wait_altitude(alt_min=-20, alt_max=-19)
|
||||
self.wait_altitude(altitude_min=-20, altitude_max=-19)
|
||||
self.set_rc(Joystick.Throttle, 1500)
|
||||
|
||||
# let the vehicle settle (momentum / stopping point shenanigans....)
|
||||
|
@ -122,7 +122,7 @@ class AutoTestSub(AutoTest):
|
|||
self.watch_altitude_maintained()
|
||||
|
||||
self.set_rc(Joystick.Throttle, 1900)
|
||||
self.wait_altitude(alt_min=-14, alt_max=-13)
|
||||
self.wait_altitude(altitude_min=-14, altitude_max=-13)
|
||||
self.set_rc(Joystick.Throttle, 1500)
|
||||
|
||||
# let the vehicle settle (momentum / stopping point shenanigans....)
|
||||
|
@ -131,7 +131,7 @@ class AutoTestSub(AutoTest):
|
|||
self.watch_altitude_maintained()
|
||||
|
||||
self.set_rc(Joystick.Throttle, 1900)
|
||||
self.wait_altitude(alt_min=-5, alt_max=-4)
|
||||
self.wait_altitude(altitude_min=-5, altitude_max=-4)
|
||||
self.set_rc(Joystick.Throttle, 1500)
|
||||
|
||||
# let the vehicle settle (momentum / stopping point shenanigans....)
|
||||
|
|
Loading…
Reference in New Issue