mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tools: autotest: add test for high-throttle-at-mode-change
This commit is contained in:
parent
0cdb1c9d1e
commit
91436c5314
@ -2362,6 +2362,23 @@ class AutoTestCopter(AutoTest):
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
||||
def fly_manual_throttle_mode_change(self):
|
||||
self.set_parameter("FS_GCS_ENABLE", 0) # avoid GUIDED instant disarm
|
||||
self.change_mode("STABILIZE")
|
||||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
self.change_mode("ACRO")
|
||||
self.change_mode("STABILIZE")
|
||||
self.change_mode("GUIDED")
|
||||
self.set_rc(3, 1700)
|
||||
self.watch_altitude_maintained(-1, 0.2) # should not take off in guided
|
||||
self.run_cmd_do_set_mode(
|
||||
"ACRO",
|
||||
want_result=mavutil.mavlink.MAV_RESULT_UNSUPPORTED) # should fix this result code!
|
||||
self.set_rc(3, 1000)
|
||||
self.run_cmd_do_set_mode("ACRO")
|
||||
self.mav.motors_disarmed_wait()
|
||||
|
||||
def test_mount_pitch(self, despitch, despitch_tolerance, timeout=5):
|
||||
tstart = self.get_sim_time()
|
||||
while True:
|
||||
@ -2953,6 +2970,10 @@ class AutoTestCopter(AutoTest):
|
||||
"Test Arming Parameter Checks",
|
||||
self.test_parameter_checks),
|
||||
|
||||
("ManualThrottleModeChange",
|
||||
"Check manual throttle mode changes denied on high throttle",
|
||||
self.fly_manual_throttle_mode_change),
|
||||
|
||||
("LogDownLoad",
|
||||
"Log download",
|
||||
lambda: self.log_download(
|
||||
|
@ -1157,30 +1157,40 @@ class AutoTest(ABC):
|
||||
self.progress("Available modes '%s'" % mode_map)
|
||||
raise ErrorException("Unknown mode '%s'" % mode)
|
||||
|
||||
def do_set_mode_via_command_long(self, mode, timeout=30):
|
||||
"""Set mode with a command long message."""
|
||||
def run_cmd_do_set_mode(self,
|
||||
mode,
|
||||
timeout=30,
|
||||
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):
|
||||
base_mode = mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED
|
||||
custom_mode = self.get_mode_from_mode_mapping(mode)
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MODE,
|
||||
base_mode,
|
||||
custom_mode,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
want_result=want_result,
|
||||
timeout=timeout
|
||||
)
|
||||
|
||||
def do_set_mode_via_command_long(self, mode, timeout=30):
|
||||
"""Set mode with a command long message."""
|
||||
tstart = self.get_sim_time()
|
||||
want_custom_mode = self.get_mode_from_mode_mapping(mode)
|
||||
while True:
|
||||
remaining = timeout - (self.get_sim_time_cached() - tstart)
|
||||
if remaining <= 0:
|
||||
raise AutoTestTimeoutException("Failed to change mode")
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MODE,
|
||||
base_mode,
|
||||
custom_mode,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
)
|
||||
self.run_cmd_do_set_mode(mode, timeout=10)
|
||||
m = self.mav.recv_match(type='HEARTBEAT',
|
||||
blocking=True,
|
||||
timeout=5)
|
||||
if m is None:
|
||||
raise ErrorException("Heartbeat not received")
|
||||
if m.custom_mode == custom_mode:
|
||||
self.progress("Got mode=%u want=%u" % (m.custom_mode, want_custom_mode))
|
||||
if m.custom_mode == want_custom_mode:
|
||||
return
|
||||
|
||||
def mavproxy_do_set_mode_via_command_long(self, mode, timeout=30):
|
||||
|
Loading…
Reference in New Issue
Block a user