mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Tools: attempt to fix Sub flapping test
This commit is contained in:
parent
805e194b0b
commit
fcafd2c685
@ -112,10 +112,10 @@ class AutoTestSub(AutoTest):
|
|||||||
msg = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True, timeout=5)
|
msg = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True, timeout=5)
|
||||||
if msg is None:
|
if msg is None:
|
||||||
raise NotAchievedException("Did not get GLOBAL_POSITION_INT")
|
raise NotAchievedException("Did not get GLOBAL_POSITION_INT")
|
||||||
pwm = 1000
|
pwm = 1300
|
||||||
if msg.relative_alt/1000.0 < -5.5:
|
if msg.relative_alt/1000.0 < -6.0:
|
||||||
# need to g`o up, not down!
|
# need to g`o up, not down!
|
||||||
pwm = 2000
|
pwm = 1700
|
||||||
self.set_rc(Joystick.Throttle, pwm)
|
self.set_rc(Joystick.Throttle, pwm)
|
||||||
self.wait_altitude(altitude_min=-6, altitude_max=-5)
|
self.wait_altitude(altitude_min=-6, altitude_max=-5)
|
||||||
self.set_rc(Joystick.Throttle, 1500)
|
self.set_rc(Joystick.Throttle, 1500)
|
||||||
|
Loading…
Reference in New Issue
Block a user