Tools/autotest: SITL reset to reset more/all16 Battery instances

This commit is contained in:
Tom Pittenger 2023-08-15 16:56:54 -07:00 committed by Andrew Tridgell
parent 93a4c3896e
commit 4d05eda6f0
2 changed files with 5 additions and 5 deletions

View File

@ -373,12 +373,12 @@ class AutoTestSub(AutoTest):
def reboot_sitl(self): def reboot_sitl(self):
"""Reboot SITL instance and wait it to reconnect.""" """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. # and wait for it to go above 50.
self.run_cmd( self.run_cmd(
mavutil.mavlink.MAV_CMD_BATTERY_RESET, mavutil.mavlink.MAV_CMD_BATTERY_RESET,
p1=255, # battery mask p1=65535, # battery mask
p2=10, # percentage p2=10, # percentage
) )
self.run_cmd_reboot() self.run_cmd_reboot()
tstart = time.time() tstart = time.time()

View File

@ -12691,8 +12691,8 @@ switch value'''
# grab a battery-remaining percentage # grab a battery-remaining percentage
self.run_cmd( self.run_cmd(
mavutil.mavlink.MAV_CMD_BATTERY_RESET, mavutil.mavlink.MAV_CMD_BATTERY_RESET,
p1=255, # battery mask p1=65535, # battery mask
p2=96, # percentage p2=96, # percentage
) )
m = self.assert_receive_message('BATTERY_STATUS', timeout=1) m = self.assert_receive_message('BATTERY_STATUS', timeout=1)
want_battery_remaining_pct = m.battery_remaining want_battery_remaining_pct = m.battery_remaining