Tools: Support MAX_RPM autotest

This commit is contained in:
Michael du Breuil 2023-04-28 13:04:13 -07:00 committed by Randy Mackay
parent 04b16d1a79
commit 29556ade25
1 changed files with 16 additions and 1 deletions

View File

@ -1143,7 +1143,7 @@ class AutoTestCopter(AutoTest):
else:
self.set_rc(3, 1700)
# we may never see ourselves as armed in a heartbeat
self.wait_statustext("Takeoff blocked: ESC RPM too low", check_context=True)
self.wait_statustext("Takeoff blocked: ESC RPM out of range", check_context=True)
self.context_pop()
self.zero_throttle()
self.disarm_vehicle()
@ -1168,6 +1168,21 @@ class AutoTestCopter(AutoTest):
self.test_takeoff_check_mode("POSHOLD")
# self.test_takeoff_check_mode("SPORT")
self.set_parameters({
"AHRS_EKF_TYPE": 10,
'SIM_ESC_TELEM': 1,
'TKOFF_RPM_MIN': 1,
'TKOFF_RPM_MAX': 3,
})
self.test_takeoff_check_mode("STABILIZE")
self.test_takeoff_check_mode("ACRO")
self.test_takeoff_check_mode("LOITER")
self.test_takeoff_check_mode("ALT_HOLD")
# self.test_takeoff_check_mode("FLOWHOLD")
self.test_takeoff_check_mode("GUIDED", True)
self.test_takeoff_check_mode("POSHOLD")
# self.test_takeoff_check_mode("SPORT")
def assert_dataflash_message_field_level_at(self,
mtype,
field,