mirror of https://github.com/ArduPilot/ardupilot
Tools/autotest: SITL reset to reset more/all16 Battery instances
This commit is contained in:
parent
93a4c3896e
commit
4d05eda6f0
|
@ -373,11 +373,11 @@ 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
|
||||
p1=65535, # battery mask
|
||||
p2=10, # percentage
|
||||
)
|
||||
self.run_cmd_reboot()
|
||||
|
|
|
@ -12691,7 +12691,7 @@ switch value'''
|
|||
# grab a battery-remaining percentage
|
||||
self.run_cmd(
|
||||
mavutil.mavlink.MAV_CMD_BATTERY_RESET,
|
||||
p1=255, # battery mask
|
||||
p1=65535, # battery mask
|
||||
p2=96, # percentage
|
||||
)
|
||||
m = self.assert_receive_message('BATTERY_STATUS', timeout=1)
|
||||
|
|
Loading…
Reference in New Issue