Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

autotest: add test showing throttle satuation problem #27114

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
18 changes: 18 additions & 0 deletions Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -5340,6 +5340,22 @@ def MinThrottle(self):
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()
Expand Down Expand Up @@ -5449,11 +5465,13 @@ def tests(self):
self.MAV_CMD_NAV_LOITER_UNLIM,
self.MAV_CMD_NAV_RETURN_TO_LAUNCH,
self.MinThrottle,
self.ClimbThrottleSaturation,
])
return ret

def disabled_tests(self):
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",
}
9 changes: 8 additions & 1 deletion Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -4225,6 +4225,7 @@ def wait_message_field_values(self,

tstart = self.get_sim_time_cached()
pass_start = None
last_debug = 0
while True:
now = self.get_sim_time_cached()
if now - tstart > timeout:
Expand All @@ -4240,8 +4241,14 @@ def wait_message_field_values(self,
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

Expand Down
Loading