diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index cf9064c3d2..2e0363feea 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -934,15 +934,21 @@ class AutoTestCopter(AutoTest): # no action taken. self.start_subtest("Batt failsafe disabled test") self.takeoffAndMoveAway() + m = self.mav.recv_match(type='BATTERY_STATUS', blocking=True, timeout=1) + if m.charge_state != mavutil.mavlink.MAV_BATTERY_CHARGE_STATE_OK: + raise NotAchievedException("Expected state ok") self.set_parameter('SIM_BATT_VOLTAGE', 11.4) self.wait_statustext("Battery 1 is low", timeout=60) + m = self.mav.recv_match(type='BATTERY_STATUS', blocking=True, timeout=1) + if m.charge_state != mavutil.mavlink.MAV_BATTERY_CHARGE_STATE_LOW: + raise NotAchievedException("Expected state low") self.delay_sim_time(5) self.wait_mode("ALT_HOLD") self.set_parameter('SIM_BATT_VOLTAGE', 10.0) self.wait_statustext("Battery 1 is critical", timeout=60) m = self.mav.recv_match(type='BATTERY_STATUS', blocking=True, timeout=1) if m.charge_state != mavutil.mavlink.MAV_BATTERY_CHARGE_STATE_CRITICAL: - raise NotAchievedException("Execpted state critical") + raise NotAchievedException("Expected state critical") self.delay_sim_time(5) self.wait_mode("ALT_HOLD") self.change_mode("RTL")