mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Tools: autotest: do not arm vehicle before flaps test
This commit is contained in:
parent
c0a990fda7
commit
6e44ea13d4
@ -709,11 +709,8 @@ class AutoTestRover(AutoTest):
|
||||
self.mavproxy.send('switch 6\n') # Manual mode
|
||||
self.wait_mode('MANUAL')
|
||||
|
||||
self.run_test("Test Sprayer", self.test_sprayer)
|
||||
|
||||
self.wait_ready_to_arm()
|
||||
self.run_test("Arm features", self.test_arm_feature)
|
||||
self.arm_vehicle()
|
||||
|
||||
self.run_test("Set modes via mavproxy switch",
|
||||
self.test_setting_modes_via_mavproxy_switch)
|
||||
@ -727,6 +724,8 @@ class AutoTestRover(AutoTest):
|
||||
self.run_test("Set modes via auxswitches",
|
||||
self.test_setting_modes_via_auxswitches)
|
||||
|
||||
self.arm_vehicle()
|
||||
|
||||
self.run_test("Drive an RTL Mission", self.drive_rtl_mission)
|
||||
|
||||
self.run_test("Learn/Drive Square with Ch7 option",
|
||||
@ -750,15 +749,15 @@ class AutoTestRover(AutoTest):
|
||||
self.mavproxy.send('switch 6\n') # Manual mode
|
||||
self.wait_mode('MANUAL')
|
||||
self.run_test("Set mode via MAV_COMMAND_DO_SET_MODE with MAVProxy",
|
||||
self.mavproxy_do_set_mode_via_command_long())
|
||||
self.mavproxy_do_set_mode_via_command_long)
|
||||
|
||||
self.run_test("Test ServoRelayEvents",
|
||||
self.test_servorelayevents)
|
||||
|
||||
self.disarm_vehicle()
|
||||
|
||||
self.run_test("Test RC overrides", self.test_rc_overrides)
|
||||
|
||||
self.run_test("Test Sprayer", self.test_sprayer)
|
||||
|
||||
self.run_test("Download logs", lambda:
|
||||
self.log_download(
|
||||
self.buildlogs_path("APMrover2-log.bin")))
|
||||
|
@ -528,6 +528,8 @@ class AutoTestPlane(AutoTest):
|
||||
ex = e
|
||||
self.context_pop()
|
||||
if ex:
|
||||
if self.armed():
|
||||
self.disarm_vehicle()
|
||||
raise ex
|
||||
|
||||
def test_rc_relay(self):
|
||||
@ -601,10 +603,12 @@ class AutoTestPlane(AutoTest):
|
||||
self.progress("Home location: %s" % self.homeloc)
|
||||
self.wait_ready_to_arm()
|
||||
self.run_test("Arm features", self.test_arm_feature)
|
||||
self.arm_vehicle()
|
||||
|
||||
self.run_test("Flaps", self.fly_flaps)
|
||||
|
||||
self.mavproxy.send('switch 6\n')
|
||||
self.wait_mode('MANUAL')
|
||||
|
||||
self.run_test("Takeoff", self.takeoff)
|
||||
|
||||
self.run_test("Fly left circuit", self.fly_left_circuit)
|
||||
|
@ -343,7 +343,6 @@ class AutoTest(ABC):
|
||||
|
||||
def log_download(self, filename, timeout=360):
|
||||
"""Download latest log."""
|
||||
self.disarm_vehicle()
|
||||
self.mav.wait_heartbeat()
|
||||
self.mavproxy.send("log list\n")
|
||||
self.mavproxy.expect("numLogs")
|
||||
@ -409,6 +408,7 @@ class AutoTest(ABC):
|
||||
self.mavproxy.send('rc %u %u\n' % (chan, pwm))
|
||||
m = self.mav.recv_match(type='RC_CHANNELS', blocking=True)
|
||||
chan_pwm = getattr(m, "chan" + str(chan) + "_raw")
|
||||
self.progress("set_rc: want=%fu got=%u" % (pwm, chan_pwm))
|
||||
if chan_pwm == pwm:
|
||||
return True
|
||||
self.progress("Failed to send RC commands to channel %s" % str(chan))
|
||||
|
Loading…
Reference in New Issue
Block a user