mirror of https://github.com/ArduPilot/ardupilot
autotest: Fix watch_altitude_maintained for Copter
This commit is contained in:
parent
109d0286d9
commit
61bb575422
|
@ -264,27 +264,17 @@ class AutoTestCopter(AutoTest):
|
||||||
|
|
||||||
self.do_RTL()
|
self.do_RTL()
|
||||||
|
|
||||||
def watch_altitude_maintained(self, min_alt, max_alt, timeout=10):
|
|
||||||
'''watch alt, relative alt must remain between min_alt and max_alt'''
|
|
||||||
tstart = self.get_sim_time_cached()
|
|
||||||
while True:
|
|
||||||
if self.get_sim_time_cached() - tstart > timeout:
|
|
||||||
return
|
|
||||||
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
|
|
||||||
if m.alt <= min_alt:
|
|
||||||
raise NotAchievedException("Altitude not maintained: want >%f got=%f" % (min_alt, m.alt))
|
|
||||||
|
|
||||||
def ModeAltHold(self):
|
def ModeAltHold(self):
|
||||||
'''Test AltHold Mode'''
|
'''Test AltHold Mode'''
|
||||||
self.takeoff(10, mode="ALT_HOLD")
|
self.takeoff(10, mode="ALT_HOLD")
|
||||||
self.watch_altitude_maintained(9, 11, timeout=5)
|
self.watch_altitude_maintained(altitude_min=9, altitude_max=11)
|
||||||
# feed in full elevator and aileron input and make sure we
|
# feed in full elevator and aileron input and make sure we
|
||||||
# retain altitude:
|
# retain altitude:
|
||||||
self.set_rc_from_map({
|
self.set_rc_from_map({
|
||||||
1: 1000,
|
1: 1000,
|
||||||
2: 1000,
|
2: 1000,
|
||||||
})
|
})
|
||||||
self.watch_altitude_maintained(9, 11, timeout=5)
|
self.watch_altitude_maintained(altitude_min=9, altitude_max=11)
|
||||||
self.set_rc_from_map({
|
self.set_rc_from_map({
|
||||||
1: 1500,
|
1: 1500,
|
||||||
2: 1500,
|
2: 1500,
|
||||||
|
@ -4572,7 +4562,7 @@ class AutoTestCopter(AutoTest):
|
||||||
self.change_mode("STABILIZE")
|
self.change_mode("STABILIZE")
|
||||||
self.change_mode("GUIDED")
|
self.change_mode("GUIDED")
|
||||||
self.set_rc(3, 1700)
|
self.set_rc(3, 1700)
|
||||||
self.watch_altitude_maintained(-1, 0.2) # should not take off in guided
|
self.watch_altitude_maintained(altitude_min=-1, altitude_max=0.2) # should not take off in guided
|
||||||
self.run_cmd_do_set_mode(
|
self.run_cmd_do_set_mode(
|
||||||
"ACRO",
|
"ACRO",
|
||||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED)
|
want_result=mavutil.mavlink.MAV_RESULT_FAILED)
|
||||||
|
|
|
@ -5837,6 +5837,14 @@ class AutoTest(ABC):
|
||||||
**kwargs
|
**kwargs
|
||||||
)
|
)
|
||||||
|
|
||||||
|
def watch_altitude_maintained(self, altitude_min, altitude_max, minimum_duration=5, relative=True):
|
||||||
|
"""Watch altitude is maintained or not between altitude_min and altitude_max during minimum_duration"""
|
||||||
|
return self.wait_altitude(altitude_min=altitude_min,
|
||||||
|
altitude_max=altitude_max,
|
||||||
|
relative=relative,
|
||||||
|
minimum_duration=minimum_duration,
|
||||||
|
timeout=minimum_duration + 1)
|
||||||
|
|
||||||
def wait_climbrate(self, speed_min, speed_max, timeout=30, **kwargs):
|
def wait_climbrate(self, speed_min, speed_max, timeout=30, **kwargs):
|
||||||
"""Wait for a given vertical rate."""
|
"""Wait for a given vertical rate."""
|
||||||
assert speed_min <= speed_max, "Minimum speed should be less than maximum speed."
|
assert speed_min <= speed_max, "Minimum speed should be less than maximum speed."
|
||||||
|
|
Loading…
Reference in New Issue