diff --git a/Tools/autotest/ardusub.py b/Tools/autotest/ardusub.py index a6af0aba9c..e78bed5de7 100644 --- a/Tools/autotest/ardusub.py +++ b/Tools/autotest/ardusub.py @@ -373,12 +373,12 @@ class AutoTestSub(AutoTest): def reboot_sitl(self): """Reboot SITL instance and wait it to reconnect.""" - # out battery is reset to full on reboot. So reduce it to 10% + # our battery is reset to full on reboot. So reduce it to 10% # and wait for it to go above 50. self.run_cmd( mavutil.mavlink.MAV_CMD_BATTERY_RESET, - p1=255, # battery mask - p2=10, # percentage + p1=65535, # battery mask + p2=10, # percentage ) self.run_cmd_reboot() tstart = time.time() diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index f0c6cde6ab..23acfa6056 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -12691,8 +12691,8 @@ switch value''' # grab a battery-remaining percentage self.run_cmd( mavutil.mavlink.MAV_CMD_BATTERY_RESET, - p1=255, # battery mask - p2=96, # percentage + p1=65535, # battery mask + p2=96, # percentage ) m = self.assert_receive_message('BATTERY_STATUS', timeout=1) want_battery_remaining_pct = m.battery_remaining