mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
autotest: add test showing throttle saturation problem
autotest: verbose minimum_duration in wait_message_field_values
This commit is contained in:
parent
9e08a98515
commit
f930ba788b
@ -5340,6 +5340,22 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
||||
self.drain_mav()
|
||||
self.assert_servo_channel_value(3, servo_min)
|
||||
|
||||
def ClimbThrottleSaturation(self):
|
||||
'''check what happens when throttle is saturated in GUIDED'''
|
||||
self.set_parameters({
|
||||
"TECS_CLMB_MAX": 30,
|
||||
"TKOFF_ALT": 1000,
|
||||
})
|
||||
|
||||
self.change_mode("TAKEOFF")
|
||||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
self.wait_message_field_values('VFR_HUD', {
|
||||
"throttle": 100,
|
||||
}, minimum_duration=30, timeout=90)
|
||||
self.disarm_vehicle(force=True)
|
||||
self.reboot_sitl()
|
||||
|
||||
def tests(self):
|
||||
'''return list of all tests'''
|
||||
ret = super(AutoTestPlane, self).tests()
|
||||
@ -5449,6 +5465,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
||||
self.MAV_CMD_NAV_LOITER_UNLIM,
|
||||
self.MAV_CMD_NAV_RETURN_TO_LAUNCH,
|
||||
self.MinThrottle,
|
||||
self.ClimbThrottleSaturation,
|
||||
])
|
||||
return ret
|
||||
|
||||
@ -5456,4 +5473,5 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
||||
return {
|
||||
"LandingDrift": "Flapping test. See https://github.com/ArduPilot/ardupilot/issues/20054",
|
||||
"InteractTest": "requires user interaction",
|
||||
"ClimbThrottleSaturation": "requires https://github.com/ArduPilot/ardupilot/pull/27106 to pass",
|
||||
}
|
||||
|
@ -4225,6 +4225,7 @@ class TestSuite(ABC):
|
||||
|
||||
tstart = self.get_sim_time_cached()
|
||||
pass_start = None
|
||||
last_debug = 0
|
||||
while True:
|
||||
now = self.get_sim_time_cached()
|
||||
if now - tstart > timeout:
|
||||
@ -4240,8 +4241,14 @@ class TestSuite(ABC):
|
||||
if pass_start is None:
|
||||
pass_start = now
|
||||
continue
|
||||
if now - pass_start < minimum_duration:
|
||||
delta = now - pass_start
|
||||
if now - last_debug >= 1:
|
||||
last_debug = now
|
||||
self.progress(f"Good field values ({delta:.2f}s/{minimum_duration}s)")
|
||||
if delta < minimum_duration:
|
||||
continue
|
||||
else:
|
||||
self.progress("Reached field values")
|
||||
return m
|
||||
pass_start = None
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user